20 namespace std_ph = std::placeholders;
23 : carma_ros2_utils::CarmaLifecycleNode(options)
45 return CallbackReturn::SUCCESS;
53 std::chrono::milliseconds(33),
56 return CallbackReturn::SUCCESS;
66 const std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Request> request,
67 std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Response> response)
69 if (
robot_enabled_ && request->set == carma_driver_msgs::srv::SetEnableRobotic::Request::ENABLE)
83 RCLCPP_DEBUG(get_logger(),
"Generating robot status message");
84 carma_driver_msgs::msg::RobotEnabled robot_status;
92#include "rclcpp_components/register_node_macro.hpp"
responsible for replicating behavior of control driver
carma_ros2_utils::ServicePtr< carma_driver_msgs::srv::SetEnableRobotic > enable_robotic_srvice_
const std::string vehicle_cmd_topic_
void vehicle_cmd_callback(const autoware_msgs::msg::VehicleCmd::UniquePtr msg)
Callback for the vehicle command topic. This callback must be triggered at least once before the enab...
carma_ros2_utils::PubPtr< carma_driver_msgs::msg::RobotEnabled > robot_status_pub_
bool enable_robotic_srv(std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_driver_msgs::srv::SetEnableRobotic::Request > request, std::shared_ptr< carma_driver_msgs::srv::SetEnableRobotic::Response > response)
Callback for the enable robotic service. Triggering this callback will modify the RobotEnabled messag...
carma_ros2_utils::SubPtr< autoware_msgs::msg::VehicleCmd > vehicle_cmd_sub_
const std::string enable_robotic_srv_
const std::string robot_status_topic_
rclcpp::TimerBase::SharedPtr spin_timer_
void publish_robot_status_callback()
Timer callback, to publish robot status message.
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
MockControllerDriver(const rclcpp::NodeOptions &)
MockControllerDriver constructor.