#include "ros/ros.h"#include "icr_msgs/SetPose.h"#include "icr_msgs/StampedContactPose.h"#include <icr_msgs/ContactState.h>#include <tf/transform_listener.h>#include <tf/message_filter.h>#include <geometry_msgs/PoseStamped.h>#include <tf/tf.h>#include <string>#include "model_server.h"#include <boost/thread/mutex.hpp>#include <boost/shared_ptr.hpp>

Go to the source code of this file.
Classes | |
| class | ICR::Phalange |
| This class represents a phalange of the hand. It subscribes to gazebo_msgs/ContactsState outputted by the sensor_bumpers and computes the average contact position and normal direction for a given target object. If the phalange is not in contact, the contact pose defaults to a predefined pose. Also, the contact pose expressed in the target object frame is computed. Note, that presently the published geometry_msgs/StampedPose message can create problems when visualizing in Rviz. This is due to the fact that Rviz only buffers 5 geometry_msgs/StampedPose msgs and proper tf transformations might not be available at the time the contact pose is published. This can be fixed by increasing the buffer size in rviz/src/rviz/default_plugin/pose_display.cpp and recompiling Rviz. Currently (in ROS Electric) there is no way to increase Rviz's tf::MessageFilter queue at runtime. Also using a topic_tools/throttle should fix the problem (did not test it though...) More... | |
Namespaces | |
| namespace | ICR |
Subscribes to gazebo_msgs/ContactsState outputted by the sensor_bumpers and computes the average contact position. | |