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_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2024 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17
19{
20 namespace std_ph = std::placeholders;
21
22 MockControllerDriver::MockControllerDriver(const rclcpp::NodeOptions &options)
23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25
26 }
27
28
29 carma_ros2_utils::CallbackReturn MockControllerDriver::handle_on_configure(const rclcpp_lifecycle::State &)
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 }
47
48 carma_ros2_utils::CallbackReturn MockControllerDriver::handle_on_activate(const rclcpp_lifecycle::State &prev_state)
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 }
58
59
60 void MockControllerDriver::vehicle_cmd_callback(const autoware_msgs::msg::VehicleCmd::UniquePtr msg)
61 {
62 robot_enabled_ = true; // If a command was received set the robot enabled status to true
63 }
64
65 bool MockControllerDriver::enable_robotic_srv(std::shared_ptr<rmw_request_id_t>,
66 const std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Request> request,
67 std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Response> response)
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 }
80
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 }
89
90} // mock_controller_driver
91
92#include "rclcpp_components/register_node_macro.hpp"
93
94// Register the component with class_loader
95RCLCPP_COMPONENTS_REGISTER_NODE(mock_controller_driver::MockControllerDriver)
responsible for replicating behavior of control driver
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_
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.