39 std::string touch_name) :
53 ROS_ERROR(
"Can't open sensor %s", touch_name.c_str());
78 std::vector <std::vector<std::string>> all_names =
get_all_names();
80 for (
unsigned int i = 0; i < all_names[0].size(); ++i)
105 int main(
int argc,
char **argv)
107 ros::init(argc, argv,
"sr_tactile_sensor");
This is the virtual implementation of the SrGenericTactileSensor. It computes virtual data...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual ~SrRealTactileSensor()
std::vector< boost::shared_ptr< SrGenericTactileSensor > > tactile_sensors
~SrRealTactileSensorManager()
int main(int argc, char **argv)
struct sensor sensor_touch
SrRealTactileSensorManager()
virtual double get_touch_data()
std::vector< std::vector< std::string > > get_all_names()
SrRealTactileSensor(std::string name, std::string touch_name)