Skip to content

Commit

Permalink
Refactor status light
Browse files Browse the repository at this point in the history
  • Loading branch information
yambati03 committed May 30, 2024
1 parent 64225a6 commit 70c7cd1
Show file tree
Hide file tree
Showing 14 changed files with 514 additions and 341 deletions.
4 changes: 2 additions & 2 deletions urc_bringup/launch/bt.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ def generate_launch_description():
"libbt_call_trigger.so",
"libbt_follow_path.so",
"libbt_update_current_pose.so",
"libbt_status_light_publisher.so"
"libbt_status_light_publisher.so",
]
node_lib_path_base = os.path.join(
Path(get_package_share_directory("urc_bt_nodes")).parent.parent.absolute(),
Expand All @@ -28,7 +28,7 @@ def generate_launch_description():
ros_lib_paths = [
os.path.join(node_lib_path_base, lib_name) for lib_name in ros_lib_names
]
bt_file_name = "bt_test.xml"
bt_file_name = "status_light.xml"

enable_color = SetEnvironmentVariable(name="RCUTILS_COLORIZED_OUTPUT", value="1")

Expand Down
56 changes: 56 additions & 0 deletions urc_bringup/launch/test_status_light.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
import os
from xacro import process_file
from launch import LaunchDescription
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from launch.actions import IncludeLaunchDescription, RegisterEventHandler
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.event_handlers import OnProcessExit


def generate_launch_description():
pkg_urc_bringup = get_package_share_directory("urc_bringup")

controller_config_file_dir = os.path.join(
pkg_urc_bringup, "config", "controller_config.yaml"
)
xacro_file = os.path.join(
get_package_share_directory("urc_hw_description"), "urdf/walli.xacro"
)
assert os.path.exists(xacro_file), "urdf path doesnt exist in " + str(xacro_file)
robot_description_config = process_file(
xacro_file, mappings={"use_simulation": "false"}
)
robot_desc = robot_description_config.toxml()

control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[controller_config_file_dir, {"robot_description": robot_desc}],
output="both",
)

load_status_light_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["-p", controller_config_file_dir, "status_light_controller"],
)

bt_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_urc_bringup, "launch", "bt.launch.py")
)
)

return LaunchDescription(
[
control_node,
load_status_light_controller,
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=load_status_light_controller,
on_exit=[bt_launch],
)
),
]
)
7 changes: 0 additions & 7 deletions urc_bringup/strategies/bt_test.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@
<LogInfo logger="{ros_log}"
message="Trying to Plan Path..."/>
</Delay>
<StatusLightPublisher topic_name="/cmd_statuslight_color" value="1"/>
<StatusLightPublisher topic_name="/cmd_statuslight_display" value="1"/>
<KeepRunningUntilFailure>
<Inverter>
<Sequence>
Expand Down Expand Up @@ -52,11 +50,6 @@
<input_port name="message"
default="&quot;Replace this with the true message.&quot;">Message to log.</input_port>
</Action>
<Action ID="StatusLightPublisher"
editable="true">
<input_port name="topic_name"/>
<input_port name="value"/>
</Action>
<Action ID="UpdateCurrentPose"
editable="true">
<input_port name="topic_name"/>
Expand Down
51 changes: 51 additions & 0 deletions urc_bringup/strategies/status_light.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
<?xml version="1.0" encoding="UTF-8"?>
<root BTCPP_format="4">
<BehaviorTree ID="test_status_light">
<RunOnce then_skip="true">
<Sequence>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="red"
state="blink"/>
</Delay>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="red"
state="off"/>
</Delay>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="green"
state="blink"/>
</Delay>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="green"
state="off"/>
</Delay>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="blue"
state="blink"/>
</Delay>
<Delay delay_msec="100">
<StatusLightPublisher topic_name="/command/status_light"
color="blue"
state="off"/>
</Delay>
</Sequence>
</RunOnce>
</BehaviorTree>

<!-- Description of Node Models (used by Groot) -->
<TreeNodesModel>
<Action ID="StatusLightPublisher"
editable="true">
<input_port name="topic_name"
default="/command/status_light"/>
<input_port name="color"/>
<input_port name="state"/>
</Action>
</TreeNodesModel>

</root>
6 changes: 4 additions & 2 deletions urc_bringup/strategies/urc_strategies.btproj
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<?xml version="1.0" encoding="UTF-8"?>
<root BTCPP_format="4" project_name="URC_Strategies">
<include path="bt_test.xml"/>
<include path="status_light.xml"/>
<include path="test_strategy.xml"/>
<!-- Description of Node Models (used by Groot) -->
<TreeNodesModel>
Expand Down Expand Up @@ -35,8 +36,9 @@
<Action ID="RecoverFromSingularity" editable="true"/>
<Action ID="ServoArm" editable="true"/>
<Action ID="StatusLightPublisher" editable="true">
<input_port name="topic_name"/>
<input_port name="value"/>
<input_port name="topic_name" default="/command/status_light"/>
<input_port name="color"/>
<input_port name="state"/>
</Action>
<Action ID="UpdateCurrentPose" editable="true">
<input_port name="topic_name"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,35 +1,72 @@
#ifndef STATUS_LIGHT_PUBLISHER_HPP__
#define STATUS_LIGHT_PUBLISHER_HPP__

#include <string>

#include "behaviortree_cpp/basic_types.h"
#include "behaviortree_cpp/tree_node.h"
#include "behaviortree_cpp/tree_node.h"
#include "behaviortree_ros2/ros_node_params.hpp"
#include "behaviortree_ros2/bt_topic_pub_node.hpp"
#include "string"
#include "std_msgs/msg/int8.hpp"

#include "urc_msgs/msg/status_light_command.hpp"

namespace behavior::actions
{
class StatusLightPublisher : public BT::RosTopicPubNode<std_msgs::msg::Int8>
{
public:
StatusLightPublisher(
const std::string & instance_name, const BT::NodeConfig & conf,
const BT::RosNodeParams & params)
: BT::RosTopicPubNode<std_msgs::msg::Int8>(instance_name, conf, params) {}

static BT::PortsList providedPorts()
int stringToColor(std::string color)
{
if (color == "red")
{
return urc_msgs::msg::StatusLightCommand::RED;
}
if (color == "green")
{
return urc_msgs::msg::StatusLightCommand::GREEN;
}
if (color == "blue")
{
return urc_msgs::msg::StatusLightCommand::BLUE;
}

throw std::invalid_argument("Invalid color!");
}

int stringToState(std::string state)
{
return providedBasicPorts(
{
BT::InputPort<std_msgs::msg::Int8>("value"),
});
if (state == "on")
{
return urc_msgs::msg::StatusLightCommand::ON;
}
if (state == "off")
{
return urc_msgs::msg::StatusLightCommand::OFF;
}
if (state == "blink")
{
return urc_msgs::msg::StatusLightCommand::BLINK;
}

throw std::invalid_argument("Invalid state!");
}

bool setMessage(std_msgs::msg::Int8 & msg) override;
class StatusLightPublisher : public BT::RosTopicPubNode<urc_msgs::msg::StatusLightCommand>
{
public:
StatusLightPublisher(
const std::string &instance_name, const BT::NodeConfig &conf,
const BT::RosNodeParams &params)
: BT::RosTopicPubNode<urc_msgs::msg::StatusLightCommand>(instance_name, conf, params) {}

static BT::PortsList providedPorts()
{
return providedBasicPorts(
{BT::InputPort<std::string>("color"),
BT::InputPort<std::string>("state")});
}

};
bool setMessage(urc_msgs::msg::StatusLightCommand &msg) override;
};
}

#endif
33 changes: 17 additions & 16 deletions urc_bt_nodes/src/actions/status_light_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,24 +4,25 @@

namespace behavior::actions
{
bool StatusLightPublisher::setMessage(std_msgs::msg::Int8 & msg)
{
msg = getInput<std_msgs::msg::Int8>("value").value();
return true;
}
}
bool StatusLightPublisher::setMessage(urc_msgs::msg::StatusLightCommand &msg)
{
std::string color = getInput<std::string>("color").value();
std::string state = getInput<std::string>("state").value();

namespace BT
{
template<>
inline std_msgs::msg::Int8 convertFromString(StringView str)
{
std_msgs::msg::Int8 output;
output.data = convertFromString<int8_t>(str);
return output;
}
} // namespace BT
try
{
msg.color = stringToColor(color);
msg.state = stringToState(state);
}
catch (std::invalid_argument &e)
{
RCLCPP_ERROR(node_->get_logger(), "Invalid argument: %s", e.what());
return false;
}

return true;
}
}

#include "behaviortree_ros2/plugins.hpp"
CreateRosNodePlugin(behavior::actions::StatusLightPublisher, "StatusLightPublisher");
74 changes: 37 additions & 37 deletions urc_controllers/include/urc_controllers/status_light_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,59 +21,59 @@
#include <sensor_msgs/msg/detail/imu__struct.hpp>
#include "std_msgs/msg/int8.hpp"
#include <std_msgs/msg/detail/int8__struct.hpp>
#include <urc_msgs/msg/status_light_command.hpp>
#include <string>
#include <vector>

namespace urc_controllers
{

class StatusLightController : public controller_interface::ControllerInterface
{
public:
StatusLightController();
class StatusLightController : public controller_interface::ControllerInterface
{
public:
StatusLightController();

controller_interface::InterfaceConfiguration command_interface_configuration() const override;
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
controller_interface::InterfaceConfiguration state_interface_configuration() const override;

controller_interface::return_type update(
const rclcpp::Time & time,
const rclcpp::Duration & period) override;
controller_interface::return_type update(
const rclcpp::Time &time,
const rclcpp::Duration &period) override;

controller_interface::CallbackReturn on_init() override;
controller_interface::CallbackReturn on_init() override;

controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state)
override;

controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state)
override;

controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state)
override;

controller_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &previous_state)
override;

controller_interface::CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_error(const rclcpp_lifecycle::State &previous_state)
override;

controller_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state)
override;
controller_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &previous_state)
override;

protected:
// status_light related
std::string status_light_name;
std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Int8>> color_command_subscriber_;
std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Int8>> display_command_subscriber_;
realtime_tools::RealtimeBuffer<double> color_command_;
realtime_tools::RealtimeBuffer<double> display_command_;
protected:
// status_light related
std::string status_light_name;
std::shared_ptr<rclcpp::Subscription<urc_msgs::msg::StatusLightCommand>> status_light_command_subscriber_;
realtime_tools::RealtimeBuffer<uint8_t> color_command_;
realtime_tools::RealtimeBuffer<uint8_t> state_command_;

// command interfaces
std::unordered_map<std::string,
std::shared_ptr<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>>
command_interface_map;
const std::vector<std::string> STATUS_LIGHT_INTERFACES{"color", "display"};
};
// command interfaces
std::unordered_map<std::string,
std::shared_ptr<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>>
command_interface_map;
const std::vector<std::string> STATUS_LIGHT_INTERFACES{"color", "state"};
};

} // namespace urc_controllers
} // namespace urc_controllers

#endif // URC_CONTROLLERS__IMU_BROADCASTER_HPP_
#endif // URC_CONTROLLERS__IMU_BROADCASTER_HPP_
Loading

0 comments on commit 70c7cd1

Please sign in to comment.