force_torque_sensor_node.cpp
Go to the documentation of this file.
3 #include <force_torque_sensor/NodeConfigurationParameters.h>
4 
5 
6 int main(int argc, char **argv)
7 {
8  ros::init(argc, argv, "force_torque_sensor_node");
9 
10  ros::AsyncSpinner spinner(4); // Use 4 threads
11  spinner.start();
12 
13  ros::NodeHandle nh("fts");
14 
15  force_torque_sensor::NodeConfigurationParameters node_params_(nh.getNamespace()+"/Node");
16 
17  node_params_.fromParamServer();
18 
19  new force_torque_sensor::ForceTorqueSensorHandle(nh, node_params_.sensor_frame,node_params_.transform_frame);
20 
21  ROS_INFO("ForceTorqueSensor Node running.");
22 
24 
25  return 0;
26 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void spinner()
#define ROS_INFO(...)
const std::string & getNamespace() const
ROSCPP_DECL void waitForShutdown()


force_torque_sensor
Author(s):
autogenerated on Fri Sep 18 2020 03:06:30