48 #include <std_srvs/Trigger.h> 62 bool srvCallback_Reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
126 ROS_INFO(
"FTC initialisation failed");
141 res.message =
"All good, you are nice person! :)";
146 res.message =
"Could not set baud rate :)";
152 res.message =
"FTS not initialised! :/";
167 res.message =
"All good, you are nice person! :)";
172 res.message =
"Could not set base identifier :)";
178 res.message =
"FTS not initialised! :/";
186 ROS_WARN(
"Going to reset NETCANOEM!");
191 res.message =
"Reset succeded!";
196 res.message =
"Reset NOT succeded!";
202 int main(
int argc,
char **argv)
204 ros::init(argc, argv,
"forcetorque_config");
207 ROS_INFO(
"ForceTorque Config Node running.");
ros::ServiceServer srvServer_SetBaseIdentifier_
bool srvCallback_Reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer srvServer_SetBaudRate_
ROSCPP_DECL void spin(Spinner &spinner)
bool SetBaudRate(int value)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool SetBaseIdentifier(int identifier)
ros::ServiceServer srvSever_Reset_
bool srvCallback_SetBaudRate(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool srvCallback_SetBaseIdentifier(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
int main(int argc, char **argv)