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.
MockControllerDriver.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2020-2021 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
20#include <autoware_msgs/VehicleCmd.h>
21#include <cav_msgs/RobotEnabled.h>
22#include <cav_srvs/SetEnableRobotic.h>
23
24namespace mock_drivers
25{
28{
29private:
30 boost::shared_ptr<ROSComms<cav_msgs::RobotEnabled>> robot_status_ptr_;
32 boost::shared_ptr<ROSComms<cav_srvs::SetEnableRobotic::Request&, cav_srvs::SetEnableRobotic::Response&>>
34
35 // Pub
36 const std::string robot_status_topic_ = "controller/robot_status";
37
38 // Sub
39 const std::string vehicle_cmd_topic_ = "vehicle_cmd";
40 const std::string enable_robotic_srv_ = "controller/enable_robotic";
41
42 // Robot Status flags
43 bool robot_active_ = false;
44 bool robot_enabled_ = false;
45
46protected:
47 int onRun() override;
48
49public:
50
56 void vehicleCmdCallback(const autoware_msgs::VehicleCmd::ConstPtr& msg);
57
66 bool enableRoboticSrv(const cav_srvs::SetEnableRobotic::Request& req, cav_srvs::SetEnableRobotic::Response& res);
67
68 // Overrides
69 MockControllerDriver(bool dummy = false);
71 bool onSpin() override;
72 std::vector<DriverType> getDriverTypes() override;
73 uint8_t getDriverStatus() override;
74 unsigned int getRate() override;
75};
76
77} // namespace mock_drivers
Mock Controller driver. Implements controller service and feedback logic to support CARMA Platform Gu...
std::vector< DriverType > getDriverTypes() override
Pure Virtual method which child classes must override that returns the list of all driver types that ...
boost::shared_ptr< ROSComms< cav_srvs::SetEnableRobotic::Request &, cav_srvs::SetEnableRobotic::Response & > > enable_robotic_ptr_
bool enableRoboticSrv(const cav_srvs::SetEnableRobotic::Request &req, cav_srvs::SetEnableRobotic::Response &res)
Callback for the enable robotic service. Triggering this callback will modify the RobotEnabled messag...
ConstPtrRefROSCommsPtr< autoware_msgs::VehicleCmd > vehicle_cmd_ptr_
boost::shared_ptr< ROSComms< cav_msgs::RobotEnabled > > robot_status_ptr_
unsigned int getRate() override
Pure virtual method that returns the desired operational rate of a child class.
int onRun() override
Pure virtual method which must be implemented by child classes. This method will be run once at start...
uint8_t getDriverStatus() override
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum fel...
bool onSpin() override
Virtual method which child classes can override to add functionality which will occur during each spi...
void vehicleCmdCallback(const autoware_msgs::VehicleCmd::ConstPtr &msg)
Callback for the vehicle command topic. This callback must be triggered at least once before the enab...
The template node for the mock drivers that will handle all of the default driver logic.
Definition: MockDriver.h:40
ROSCommsPtr< ConstPtrRef< T > > ConstPtrRefROSCommsPtr
Definition: MockDriver.h:56