Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046 #include <geometry_msgs/Pose.h>
00047 #include <geometry_msgs/Pose2D.h>
00048 #include <tf/transform_datatypes.h>
00049 #include "mocap_optitrack/mocap_config.h"
00050
00051 const std::string POSE_TOPIC_PARAM_NAME = "pose";
00052 const std::string POSE2D_TOPIC_PARAM_NAME = "pose2d";
00053 const std::string FRAME_ID_PARAM_NAME = "frame_id";
00054
00055 PublishedRigidBody::PublishedRigidBody(XmlRpc::XmlRpcValue &config_node)
00056 {
00057
00058 publish_pose = validateParam(config_node, POSE_TOPIC_PARAM_NAME);
00059 publish_pose2d = validateParam(config_node, POSE2D_TOPIC_PARAM_NAME);
00060
00061 publish_tf = validateParam(config_node, FRAME_ID_PARAM_NAME);
00062
00063 if (publish_pose)
00064 {
00065 pose_topic = (std::string&) config_node[POSE_TOPIC_PARAM_NAME];
00066 pose_pub = n.advertise<geometry_msgs::Pose>(pose_topic, 1000);
00067 }
00068
00069 if (publish_pose2d)
00070 {
00071 pose2d_topic = (std::string&) config_node[POSE2D_TOPIC_PARAM_NAME];
00072 pose2d_pub = n.advertise<geometry_msgs::Pose2D>(pose2d_topic, 1000);
00073 }
00074
00075 if (publish_tf)
00076 {
00077 frame_id = (std::string&) config_node[FRAME_ID_PARAM_NAME];
00078 }
00079 }
00080
00081 void PublishedRigidBody::publish(RigidBody &body)
00082 {
00083
00084 if (!body.has_data())
00085 {
00086 return;
00087 }
00088
00089 if (body.pose.position.x != body.pose.position.x)
00090 {
00091 return;
00092 }
00093
00094 const geometry_msgs::Pose pose = body.get_ros_pose();
00095
00096 if (publish_pose)
00097 {
00098 pose_pub.publish(pose);
00099 }
00100
00101 if (!publish_pose2d && !publish_tf)
00102 {
00103
00104 return;
00105 }
00106
00107 tf::Quaternion q(pose.orientation.x,
00108 pose.orientation.y,
00109 pose.orientation.z,
00110 pose.orientation.w);
00111
00112
00113 if (publish_pose2d)
00114 {
00115 geometry_msgs::Pose2D pose2d;
00116 pose2d.x = pose.position.x;
00117 pose2d.y = pose.position.y;
00118 pose2d.theta = tf::getYaw(q);
00119 pose2d_pub.publish(pose2d);
00120 }
00121
00122 if (publish_tf)
00123 {
00124
00125 tf::Transform transform;
00126 transform.setOrigin( tf::Vector3(pose.position.x,
00127 pose.position.y,
00128 pose.position.z));
00129
00130
00131 transform.setRotation(q);
00132 ros::Time timestamp(ros::Time::now());
00133 tf_pub.sendTransform(tf::StampedTransform(transform, timestamp, "/odom", frame_id));
00134 }
00135 }
00136
00137 bool PublishedRigidBody::validateParam(XmlRpc::XmlRpcValue &config_node, const std::string &name)
00138 {
00139 if (!config_node.hasMember(name))
00140 {
00141 return false;
00142 }
00143
00144 if (config_node[name].getType() != XmlRpc::XmlRpcValue::TypeString)
00145 {
00146 return false;
00147 }
00148
00149 return true;
00150 }
00151