44 #include "std_msgs/String.h"    45 #include "robotiq_ft_sensor/ft_sensor.h"    46 #include "robotiq_ft_sensor/sensor_accessor.h"    57         ROS_INFO(
"I heard: FX[%f] FY[%f] FZ[%f] MX[%f] MY[%f] MZ[%f]", msg.Fx,msg.Fy,msg.Fz,msg.Mx,msg.My,msg.Mz);
    63 int main(
int argc, 
char **argv)
    74         robotiq_ft_sensor::sensor_accessor srv;
    79         if(count == 10000000){
    85                 srv.request.command_id = srv.request.COMMAND_SET_ZERO;
    88                         ROS_INFO(
"ret: %s", srv.response.res.c_str());
 ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
void reCallback(const robotiq_ft_sensor::ft_sensor &msg)