Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
mock_controller_driver::MockControllerDriver Class Reference

responsible for replicating behavior of control driver More...

#include <mock_controller_driver_node.hpp>

Inheritance diagram for mock_controller_driver::MockControllerDriver:
Inheritance graph
Collaboration diagram for mock_controller_driver::MockControllerDriver:
Collaboration graph

Public Member Functions

 MockControllerDriver (const rclcpp::NodeOptions &)
 MockControllerDriver constructor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Callback for dynamic parameter updates. More...
 
void publish_robot_status_callback ()
 Timer callback, to publish robot status message. More...
 
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 message output by this driver. This service enables the robotic drive-by-wire controller. More...
 
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 enable robotic service is called. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &prev_state)
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &)
 

Public Attributes

const std::string robot_status_topic_ = "controller/robot_status"
 
const std::string vehicle_cmd_topic_ = "vehicle_cmd"
 
const std::string enable_robotic_srv_ = "controller/enable_robotic"
 
bool robot_active_ = false
 
bool robot_enabled_ = false
 

Private Attributes

carma_ros2_utils::SubPtr< autoware_msgs::msg::VehicleCmd > vehicle_cmd_sub_
 
carma_ros2_utils::PubPtr< carma_driver_msgs::msg::RobotEnabled > robot_status_pub_
 
carma_ros2_utils::ServicePtr< carma_driver_msgs::srv::SetEnableRobotic > enable_robotic_srvice_
 
rclcpp::TimerBase::SharedPtr spin_timer_
 

Detailed Description

responsible for replicating behavior of control driver

Definition at line 37 of file mock_controller_driver_node.hpp.

Constructor & Destructor Documentation

◆ MockControllerDriver()

mock_controller_driver::MockControllerDriver::MockControllerDriver ( const rclcpp::NodeOptions &  options)
explicit

MockControllerDriver constructor.

Definition at line 22 of file mock_controller_driver_node.cpp.

23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25
26 }

Member Function Documentation

◆ enable_robotic_srv()

bool mock_controller_driver::MockControllerDriver::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 message output by this driver. This service enables the robotic drive-by-wire controller.

Parameters
requestThe service request in message
responseThe service response out message
Returns
Flag idicating if the service was processed successfully.

Definition at line 65 of file mock_controller_driver_node.cpp.

68 {
69 if (robot_enabled_ && request->set == carma_driver_msgs::srv::SetEnableRobotic::Request::ENABLE)
70 {
71 robot_active_ = true;
72 }
73 else
74 {
75 robot_active_ = false;
76 }
77
78 return true;
79 }

References robot_active_, and robot_enabled_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn mock_controller_driver::MockControllerDriver::handle_on_activate ( const rclcpp_lifecycle::State &  prev_state)

Definition at line 48 of file mock_controller_driver_node.cpp.

49 {
50 // Setup timers
51 spin_timer_ = create_timer(
52 get_clock(),
53 std::chrono::milliseconds(33), // 30 Hz
55
56 return CallbackReturn::SUCCESS;
57 }
void publish_robot_status_callback()
Timer callback, to publish robot status message.

References publish_robot_status_callback(), and spin_timer_.

Here is the call graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn mock_controller_driver::MockControllerDriver::handle_on_configure ( const rclcpp_lifecycle::State &  prev_state)

Definition at line 29 of file mock_controller_driver_node.cpp.

30 {
31
32 // Setup subscribers
33 vehicle_cmd_sub_ = create_subscription<autoware_msgs::msg::VehicleCmd>(vehicle_cmd_topic_, 10,
34 std::bind(&MockControllerDriver::vehicle_cmd_callback, this, std_ph::_1));
35
36 // Setup publishers
37 robot_status_pub_ = create_publisher<carma_driver_msgs::msg::RobotEnabled>(robot_status_topic_, 10);
38
39 // Setup service servers
40 enable_robotic_srvice_ = create_service<carma_driver_msgs::srv::SetEnableRobotic>(enable_robotic_srv_,
41 std::bind(&MockControllerDriver::enable_robotic_srv, this, std_ph::_1, std_ph::_2, std_ph::_3));
42
43
44 // Return success if everything initialized successfully
45 return CallbackReturn::SUCCESS;
46 }
carma_ros2_utils::ServicePtr< carma_driver_msgs::srv::SetEnableRobotic > enable_robotic_srvice_
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_

References enable_robotic_srv(), enable_robotic_srv_, enable_robotic_srvice_, robot_status_pub_, robot_status_topic_, vehicle_cmd_callback(), vehicle_cmd_sub_, and vehicle_cmd_topic_.

Here is the call graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult mock_controller_driver::MockControllerDriver::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Callback for dynamic parameter updates.

◆ publish_robot_status_callback()

void mock_controller_driver::MockControllerDriver::publish_robot_status_callback ( )

Timer callback, to publish robot status message.

Definition at line 81 of file mock_controller_driver_node.cpp.

82 {
83 RCLCPP_DEBUG(get_logger(), "Generating robot status message");
84 carma_driver_msgs::msg::RobotEnabled robot_status;
85 robot_status.robot_active = robot_active_;
86 robot_status.robot_enabled = robot_enabled_;
87 robot_status_pub_->publish(robot_status);
88 }

References robot_active_, robot_enabled_, and robot_status_pub_.

Referenced by handle_on_activate().

Here is the caller graph for this function:

◆ vehicle_cmd_callback()

void mock_controller_driver::MockControllerDriver::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 enable robotic service is called.

Parameters
msgThe vehicle command to receive

Definition at line 60 of file mock_controller_driver_node.cpp.

61 {
62 robot_enabled_ = true; // If a command was received set the robot enabled status to true
63 }

References robot_enabled_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ enable_robotic_srv_

const std::string mock_controller_driver::MockControllerDriver::enable_robotic_srv_ = "controller/enable_robotic"

Definition at line 64 of file mock_controller_driver_node.hpp.

Referenced by handle_on_configure().

◆ enable_robotic_srvice_

carma_ros2_utils::ServicePtr<carma_driver_msgs::srv::SetEnableRobotic> mock_controller_driver::MockControllerDriver::enable_robotic_srvice_
private

Definition at line 49 of file mock_controller_driver_node.hpp.

Referenced by handle_on_configure().

◆ robot_active_

bool mock_controller_driver::MockControllerDriver::robot_active_ = false

◆ robot_enabled_

bool mock_controller_driver::MockControllerDriver::robot_enabled_ = false

◆ robot_status_pub_

carma_ros2_utils::PubPtr<carma_driver_msgs::msg::RobotEnabled> mock_controller_driver::MockControllerDriver::robot_status_pub_
private

◆ robot_status_topic_

const std::string mock_controller_driver::MockControllerDriver::robot_status_topic_ = "controller/robot_status"

Definition at line 58 of file mock_controller_driver_node.hpp.

Referenced by handle_on_configure().

◆ spin_timer_

rclcpp::TimerBase::SharedPtr mock_controller_driver::MockControllerDriver::spin_timer_
private

Definition at line 52 of file mock_controller_driver_node.hpp.

Referenced by handle_on_activate().

◆ vehicle_cmd_sub_

carma_ros2_utils::SubPtr<autoware_msgs::msg::VehicleCmd> mock_controller_driver::MockControllerDriver::vehicle_cmd_sub_
private

Definition at line 42 of file mock_controller_driver_node.hpp.

Referenced by handle_on_configure().

◆ vehicle_cmd_topic_

const std::string mock_controller_driver::MockControllerDriver::vehicle_cmd_topic_ = "vehicle_cmd"

Definition at line 61 of file mock_controller_driver_node.hpp.

Referenced by handle_on_configure().


The documentation for this class was generated from the following files: