22 #include <dynamic_reconfigure/server.h> 23 #include <prbt_hardware_support/FakeSpeedOverrideConfig.h> 24 #include <prbt_hardware_support/GetSpeedOverride.h> 30 config.speed_override);
35 prbt_hardware_support::GetSpeedOverride::Response &res)
41 int main(
int argc,
char **argv) {
42 ros::init(argc, argv,
"fake_speed_override");
47 dynamic_reconfigure::Server<prbt_hardware_support::FakeSpeedOverrideConfig> server;
48 dynamic_reconfigure::Server<prbt_hardware_support::FakeSpeedOverrideConfig>::CallbackType
f;
51 server.setCallback(f);
void dynamic_set_speed_override(prbt_hardware_support::FakeSpeedOverrideConfig &config, uint32_t level)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::atomic< double > SPEED_OVERRIDE
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ROSCPP_DECL void spin(Spinner &spinner)
bool getSpeedOverride(prbt_hardware_support::GetSpeedOverride::Request &, prbt_hardware_support::GetSpeedOverride::Response &res)