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 #include "TransformBroadcaster.h"
00033
00034 TransformBroadcaster::TransformBroadcaster(const QString &parent_frame, const QString &child_frame, QObject *parent) :
00035 QObject(parent), valid_(false), enabled_(false)
00036 {
00037 setPosition(0,0,0);
00038 setQuaternion(0,0,0,1);
00039
00040 setParentFrame(parent_frame);
00041 setChildFrame(child_frame);
00042
00043 enabled_ = true;
00044 check(); send();
00045 }
00046
00047 const geometry_msgs::TransformStamped &TransformBroadcaster::value() const
00048 {
00049 return msg_;
00050 }
00051
00052 void TransformBroadcaster::setValue(const geometry_msgs::TransformStamped &tf)
00053 {
00054 msg_ = tf;
00055 check(); send();
00056 }
00057
00058 void TransformBroadcaster::setPose(const geometry_msgs::Pose &pose)
00059 {
00060 bool old = enabled_;
00061 enabled_ = false;
00062
00063 const geometry_msgs::Point &p = pose.position;
00064 setPosition(p.x, p.y, p.z);
00065
00066 const geometry_msgs::Quaternion &q = pose.orientation;
00067 setQuaternion(q.x, q.y, q.z, q.w);
00068
00069 enabled_ = old;
00070 send();
00071 }
00072
00073 bool TransformBroadcaster::enabled() const
00074 {
00075 return enabled_;
00076 }
00077
00078 void TransformBroadcaster::setEnabled(bool bEnabled)
00079 {
00080 enabled_ = bEnabled;
00081 check(); send();
00082 }
00083
00084 void TransformBroadcaster::setDisabled(bool bDisabled)
00085 {
00086 setEnabled(!bDisabled);
00087 }
00088
00089 void TransformBroadcaster::setParentFrame(const QString &frame)
00090 {
00091 msg_.header.frame_id = frame.toStdString();
00092 check(); send();
00093 }
00094
00095 void TransformBroadcaster::setChildFrame(const QString &frame)
00096 {
00097 msg_.child_frame_id = frame.toStdString();
00098 check(); send();
00099 }
00100
00101 void TransformBroadcaster::setPosition(const Eigen::Vector3d &p)
00102 {
00103 setPosition(p.x(), p.y(), p.z());
00104 }
00105
00106 void TransformBroadcaster::setQuaternion(const Eigen::Quaterniond &q)
00107 {
00108 setQuaternion(q.x(), q.y(), q.z(), q.w());
00109 }
00110
00111 void TransformBroadcaster::setPosition(double x, double y, double z)
00112 {
00113 msg_.transform.translation.x = x;
00114 msg_.transform.translation.y = y;
00115 msg_.transform.translation.z = z;
00116 send();
00117 }
00118
00119 void TransformBroadcaster::setQuaternion(double x, double y, double z, double w)
00120 {
00121 msg_.transform.rotation.x = x;
00122 msg_.transform.rotation.y = y;
00123 msg_.transform.rotation.z = z;
00124 msg_.transform.rotation.w = w;
00125 send();
00126 }
00127
00128 void TransformBroadcaster::send()
00129 {
00130 if (enabled_ && valid_) {
00131 msg_.header.stamp = ros::Time::now();
00132 ++msg_.header.seq;
00133 broadcaster_.sendTransform(msg_);
00134 ros::spinOnce();
00135 }
00136 }
00137
00138 void TransformBroadcaster::check()
00139 {
00140 valid_ =
00141 !msg_.header.frame_id.empty() &&
00142 !msg_.child_frame_id.empty() &&
00143 msg_.header.frame_id != msg_.child_frame_id;
00144 }