Class aquiring object poses from a pose source and broadcasting the object's pose to tf. More...
#include <pose_broadcaster.h>
Public Member Functions | |
void | broadcastPose () |
Broadcasts the object's pose. | |
bool | getPoseUC3MObjtrack () |
Not implemented yet! intended to get the pose from the UC3M objectracker by fitting PoseBroadcaster::obj_cloud_ to the blob detected by the kinect Takes a tf::Transform reference and writes the acquired pose to it. | |
bool | isPoseSourceUC3M () |
True if pose broadcaster is configured to get the pose of an object from uc3m_objtracker. | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | PoseBroadcaster () |
void | setObject (pcl::PointCloud< pcl::PointNormal > const &obj_cloud, std::string const &obj_name) |
Sets the object for which the pose will be broadcasted. | |
~PoseBroadcaster () | |
Private Member Functions | |
bool | getPoseGazebo () |
Gets the pose from a client call to Gazebo's /get_model_state service Takes a tf::Transform reference and writes the acquired pose to it. | |
Private Attributes | |
std::string | camera_frame_id_ |
ros::ServiceClient | gazebo_get_ms_clt_ |
ros::ServiceClient | get_tracked_obj_ |
boost::mutex | lock_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
pcl::PointCloud< pcl::PointNormal > | obj_cloud_ |
Point cloud describing the object geometry. | |
std::string | obj_name_ |
tf::Transform | object_pose_ |
The pose that is broadcasted in broadcastPose. | |
std::string | pose_source_ |
Describes the pose source. Can be either one of "gazebo" or "uc3m_objtrack". | |
std::string | ref_frame_id_ |
Frame in which the object's pose is expressed in. | |
tf::TransformBroadcaster | tf_brc_ |
tf::TransformListener | tf_list_ |
Class aquiring object poses from a pose source and broadcasting the object's pose to tf.
Definition at line 26 of file pose_broadcaster.h.
Definition at line 14 of file pose_broadcaster.cpp.
ICR::PoseBroadcaster::~PoseBroadcaster | ( | ) | [inline] |
Definition at line 35 of file pose_broadcaster.h.
void ICR::PoseBroadcaster::broadcastPose | ( | ) |
Broadcasts the object's pose.
Definition at line 58 of file pose_broadcaster.cpp.
bool ICR::PoseBroadcaster::getPoseGazebo | ( | ) | [private] |
Gets the pose from a client call to Gazebo's /get_model_state service Takes a tf::Transform reference and writes the acquired pose to it.
Definition at line 97 of file pose_broadcaster.cpp.
Not implemented yet! intended to get the pose from the UC3M objectracker by fitting PoseBroadcaster::obj_cloud_ to the blob detected by the kinect Takes a tf::Transform reference and writes the acquired pose to it.
Definition at line 113 of file pose_broadcaster.cpp.
bool ICR::PoseBroadcaster::isPoseSourceUC3M | ( | ) | [inline] |
True if pose broadcaster is configured to get the pose of an object from uc3m_objtracker.
Definition at line 50 of file pose_broadcaster.h.
void ICR::PoseBroadcaster::setObject | ( | pcl::PointCloud< pcl::PointNormal > const & | obj_cloud, |
std::string const & | obj_name | ||
) |
Sets the object for which the pose will be broadcasted.
Definition at line 50 of file pose_broadcaster.cpp.
std::string ICR::PoseBroadcaster::camera_frame_id_ [private] |
Definition at line 85 of file pose_broadcaster.h.
ros::ServiceClient ICR::PoseBroadcaster::gazebo_get_ms_clt_ [private] |
Definition at line 86 of file pose_broadcaster.h.
ros::ServiceClient ICR::PoseBroadcaster::get_tracked_obj_ [private] |
Definition at line 87 of file pose_broadcaster.h.
boost::mutex ICR::PoseBroadcaster::lock_ [private] |
Definition at line 62 of file pose_broadcaster.h.
ros::NodeHandle ICR::PoseBroadcaster::nh_ [private] |
Definition at line 61 of file pose_broadcaster.h.
ros::NodeHandle ICR::PoseBroadcaster::nh_private_ [private] |
Definition at line 61 of file pose_broadcaster.h.
pcl::PointCloud<pcl::PointNormal> ICR::PoseBroadcaster::obj_cloud_ [private] |
Point cloud describing the object geometry.
Definition at line 73 of file pose_broadcaster.h.
std::string ICR::PoseBroadcaster::obj_name_ [private] |
Definition at line 74 of file pose_broadcaster.h.
The pose that is broadcasted in broadcastPose.
Definition at line 67 of file pose_broadcaster.h.
std::string ICR::PoseBroadcaster::pose_source_ [private] |
Describes the pose source. Can be either one of "gazebo" or "uc3m_objtrack".
Definition at line 79 of file pose_broadcaster.h.
std::string ICR::PoseBroadcaster::ref_frame_id_ [private] |
Frame in which the object's pose is expressed in.
Definition at line 84 of file pose_broadcaster.h.
tf::TransformBroadcaster ICR::PoseBroadcaster::tf_brc_ [private] |
Definition at line 63 of file pose_broadcaster.h.
tf::TransformListener ICR::PoseBroadcaster::tf_list_ [private] |
Definition at line 89 of file pose_broadcaster.h.