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.hpp
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 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <functional>
21#include <std_msgs/msg/string.hpp>
22#include <std_srvs/srv/empty.hpp>
23
24#include <carma_driver_msgs/srv/set_enable_robotic.hpp>
25#include <carma_driver_msgs/msg/robot_enabled.hpp>
26#include <autoware_msgs/msg/vehicle_cmd.hpp>
27#include <carma_ros2_utils/carma_lifecycle_node.hpp>
28
30{
31
37 class MockControllerDriver : public carma_ros2_utils::CarmaLifecycleNode
38 {
39
40 private:
41 // Subscribers
42 carma_ros2_utils::SubPtr<autoware_msgs::msg::VehicleCmd> vehicle_cmd_sub_;
43
44 // Publishers
45 carma_ros2_utils::PubPtr<carma_driver_msgs::msg::RobotEnabled> robot_status_pub_;
46
47
48 // Service Servers
49 carma_ros2_utils::ServicePtr<carma_driver_msgs::srv::SetEnableRobotic> enable_robotic_srvice_;
50
51 // Timers
52 rclcpp::TimerBase::SharedPtr spin_timer_;
53
54
55 public:
56
57 // Pub
58 const std::string robot_status_topic_ = "controller/robot_status";
59
60 // Sub
61 const std::string vehicle_cmd_topic_ = "vehicle_cmd";
62
63 // Service
64 const std::string enable_robotic_srv_ = "controller/enable_robotic";
65
66 // Robot Status flags
67 bool robot_active_ = false;
68 bool robot_enabled_ = false;
69
73 explicit MockControllerDriver(const rclcpp::NodeOptions &);
74
78 rcl_interfaces::msg::SetParametersResult
79 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
80
85
86
96 bool enable_robotic_srv(std::shared_ptr<rmw_request_id_t>,
97 const std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Request> request,
98 std::shared_ptr<carma_driver_msgs::srv::SetEnableRobotic::Response> response);
99
105 void vehicle_cmd_callback(const autoware_msgs::msg::VehicleCmd::UniquePtr msg);
106
108 // Overrides
110 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state);
111 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
112
113 };
114
115} // mock_controller_driver
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.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
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.