Go to the documentation of this file.
6 #include <std_srvs/Empty.h>
11 typedef diagnostic_msgs::DiagnosticStatus
DS;
34 ROS_INFO(
"Starting initialization timer...");
62 "swri::ServiceServer test service 1",
this,
66 "swri::ServiceServer test service 2",
this,
70 "swri::ServiceServer test service 3",
this,
79 std_srvs::Empty::Response &res)
81 ROS_INFO(
"test service 1 called. returning %s",
87 std_srvs::Empty::Response> &event)
95 const std_srvs::Empty::Request &request,
96 std_srvs::Empty::Response &response)
109 status.
summary(DS::OK,
"No errors reported.");
116 status.
summary(DS::OK,
"No errors reported.");
123 status.
summary(DS::OK,
"No errors reported.");
129 int main(
int argc,
char **argv)
131 ros::init(argc, argv,
"service_server_test");
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
swri::ServiceServer test1_srv_
void service3Diagnostics(du::DiagnosticStatusWrapper &status)
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
void summary(const diagnostic_msgs::DiagnosticStatus &src)
swri::ServiceServer test3_srv_
void service2Diagnostics(du::DiagnosticStatusWrapper &status)
bool handleService3(const std::string &name, const std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
ros::WallTimer init_timer_
void setHardwareID(const std::string &hwid)
swri::ServiceServer test2_srv_
void setInstrumentPerClient(bool enable)
void service1Diagnostics(du::DiagnosticStatusWrapper &status)
void handleDiagnosticsTimer(const ros::TimerEvent &ignored)
du::Updater diagnostic_updater_
void initialize(const ros::WallTimerEvent &ignored)
diagnostic_msgs::DiagnosticStatus DS
bool handleService1(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void add(const std::string &name, TaskFunction f)
int main(int argc, char **argv)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void setLogCalls(bool enable)
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
bool handleService2(ros::ServiceEvent< std_srvs::Empty::Request, std_srvs::Empty::Response > &event)
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15