28 return cav_msgs::DriverStatus::OPERATIONAL;
unsigned int getRate() override
Pure virtual method that returns the desired operational rate of a child class.
std::vector< DriverType > getDriverTypes() override
Pure Virtual method which child classes must override that returns the list of all driver types that ...
const std::string vehicle_twist
const std::string brake_position_topic_
MockCANDriver(bool dummy=false)
const std::string steering_wheel_angle_topic_
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...
const std::string transmission_state_topic_
Node class which connects to the ROS network.
const std::string bag_prefix_
MockDriverNode mock_driver_node_