#include <atomic>
#include <ros/ros.h>
#include <dynamic_reconfigure/server.h>
#include <pilz_msgs/GetSpeedOverride.h>
#include <prbt_hardware_support/FakeSpeedOverrideConfig.h>
Go to the source code of this file.
|
void | dynamic_set_speed_override (prbt_hardware_support::FakeSpeedOverrideConfig &config, uint32_t level) |
|
bool | getSpeedOverride (pilz_msgs::GetSpeedOverride::Request &, pilz_msgs::GetSpeedOverride::Response &res) |
|
int | main (int argc, char **argv) |
|
◆ dynamic_set_speed_override()
void dynamic_set_speed_override |
( |
prbt_hardware_support::FakeSpeedOverrideConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
◆ getSpeedOverride()
bool getSpeedOverride |
( |
pilz_msgs::GetSpeedOverride::Request & |
, |
|
|
pilz_msgs::GetSpeedOverride::Response & |
res |
|
) |
| |
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ SPEED_OVERRIDE
std::atomic<double> SPEED_OVERRIDE { 1.0 } |