cnoid_ros_utils
PosePublisherItem.cpp
Go to the documentation of this file.
1 /* Author: Masaki Murooka */
2 
3 #include <cnoid/BodyItem>
4 #include <cnoid/DyBody>
5 #include <cnoid/ItemManager>
6 #include <cnoid/MessageView>
7 #include <cnoid/PutPropertyFunction>
8 #include <cnoid/RootItem>
9 
10 #include <geometry_msgs/PoseStamped.h>
11 #include <geometry_msgs/TransformStamped.h>
12 #include <geometry_msgs/TwistStamped.h>
13 
14 #include "PosePublisherItem.h"
15 
16 using namespace CnoidRosUtils;
17 
18 void PosePublisherItem::initialize(cnoid::ExtensionManager * ext)
19 {
20  int argc = 0;
21  char ** argv;
22  if(!ros::isInitialized())
23  {
24  ros::init(argc, argv, "choreonoid_ros");
25  }
26 
27  if(!initialized_)
28  {
29  ext->itemManager().registerClass<PosePublisherItem>("CnoidRosUtils::PosePublisherItem");
30  ext->itemManager().addCreationPanel<PosePublisherItem>();
31  initialized_ = true;
32  }
33 }
34 
36 {
37  cnoid::RootItem::instance()->sigTreeChanged().connect(boost::bind(&PosePublisherItem::setup, this));
38 }
39 
41 {
42  cnoid::RootItem::instance()->sigTreeChanged().connect(boost::bind(&PosePublisherItem::setup, this));
43  hooked_sims_.clear();
45  sim_cnt_ = 0;
46 }
47 
49 {
50  stop();
51 }
52 
53 cnoid::Item * PosePublisherItem::doDuplicate() const
54 {
55  return new PosePublisherItem(*this);
56 }
57 
58 void PosePublisherItem::doPutProperties(cnoid::PutPropertyFunction & putProperty)
59 {
60  cnoid::Item::doPutProperties(putProperty);
61  putProperty("Link name", link_name_, cnoid::changeProperty(link_name_));
62  putProperty("Frame id", frame_id_, cnoid::changeProperty(frame_id_));
63  putProperty("Pose topic name (only for topic output)", pose_topic_name_, cnoid::changeProperty(pose_topic_name_));
64  putProperty("Velocity topic name (only for topic output)", vel_topic_name_, cnoid::changeProperty(vel_topic_name_));
65  putProperty("TF frame id (only for TF output)", tf_child_frame_id_, cnoid::changeProperty(tf_child_frame_id_));
66  putProperty("Publish rate", pub_rate_, [&](const double & pub_rate) {
67  pub_rate_ = std::min(std::max(pub_rate, 1e-1), 1e3);
68  if(sim_)
69  {
71  }
72  return true;
73  });
74  putProperty("Output TF", output_tf_, cnoid::changeProperty(output_tf_));
75 }
76 
77 bool PosePublisherItem::store(cnoid::Archive & archive)
78 {
79  archive.write("Link name", link_name_);
80  archive.write("Frame id", frame_id_);
81  archive.write("Pose topic name (only for topic output)", pose_topic_name_);
82  archive.write("Velocity topic name (only for topic output)", vel_topic_name_);
83  archive.write("TF frame id (only for TF output)", tf_child_frame_id_);
84  archive.write("Publish rate", pub_rate_);
85  archive.write("Output TF", output_tf_);
86 
87  return true;
88 }
89 
90 bool PosePublisherItem::restore(const cnoid::Archive & archive)
91 {
92  archive.read("Link name", link_name_);
93  archive.read("Frame id", frame_id_);
94  archive.read("Pose topic name (only for topic output)", pose_topic_name_);
95  archive.read("Velocity topic name (only for topic output)", vel_topic_name_);
96  archive.read("TF frame id (only for TF output)", tf_child_frame_id_);
97  archive.read("Publish rate", pub_rate_);
98  archive.read("Output TF", output_tf_);
99 
100  return true;
101 }
102 
104 {
105  // Get WorldItem
106  world_ = this->findOwnerItem<cnoid::WorldItem>();
107  if(!world_)
108  {
109  // cnoid::MessageView::instance()->putln("[PosePublisherItem] WorldItem not found", cnoid::MessageView::ERROR);
110  return;
111  }
112 
113  // Set hook functions for simulation start and stop
114  for(cnoid::Item * child = world_->childItem(); child; child = child->nextItem())
115  {
116  cnoid::SimulatorItemPtr sim = dynamic_cast<cnoid::SimulatorItem *>(child);
117  if(sim && !sim->isRunning() && !hooked_sims_.count(sim->name()))
118  {
119  sim->sigSimulationStarted().connect(std::bind(&PosePublisherItem::start, this));
120  sim->sigSimulationFinished().connect(std::bind(&PosePublisherItem::stop, this));
121  hooked_sims_.insert(sim->name());
122  }
123  }
124 }
125 
127 {
128  // Get SimulatorItem
129  sim_ = cnoid::SimulatorItem::findActiveSimulatorItemFor(this);
130  if(!sim_)
131  {
132  cnoid::MessageView::instance()->putln("[PosePublisherItem] SimulatorItem not found", cnoid::MessageView::ERROR);
133  return false;
134  }
135 
136  // Get BodyItem
137  body_item_ = this->findOwnerItem<cnoid::BodyItem>();
138  if(!body_item_)
139  {
140  cnoid::MessageView::instance()->putln("[PosePublisherItem] Owner BodyItem not found", cnoid::MessageView::ERROR);
141  return false;
142  }
143 
144  // Setup ROS
145  nh_ = std::make_shared<ros::NodeHandle>();
146 
147  if(pose_topic_name_.empty())
148  {
149  pose_topic_name_ = "cnoid/" + body_item_->name() + "/pose";
150  }
151  if(vel_topic_name_.empty())
152  {
153  vel_topic_name_ = "cnoid/" + body_item_->name() + "/vel";
154  }
155  if(frame_id_.empty())
156  {
157  frame_id_ = "robot_map";
158  }
159  if(tf_child_frame_id_.empty())
160  {
162  }
163  pose_pub_ = nh_->advertise<geometry_msgs::PoseStamped>(pose_topic_name_, 1);
164  vel_pub_ = nh_->advertise<geometry_msgs::TwistStamped>(vel_topic_name_, 1);
165  pub_skip_ = getPubSkip();
166 
167  // Add postDynamicsFunction
168  post_dynamics_func_id_ = sim_->addPostDynamicsFunction(std::bind(&PosePublisherItem::onPostDynamics, this));
169 
170  return true;
171 }
172 
174 {
175  // Remove postDynamicsFunction
176  if(post_dynamics_func_id_ != -1)
177  {
178  sim_->removePostDynamicsFunction(post_dynamics_func_id_);
180  }
181 }
182 
184 {
185  sim_cnt_++;
186  if(sim_cnt_ % pub_skip_ != 0)
187  {
188  return;
189  }
190 
191  // Get SimulationBody
192  cnoid::SimulationBody * sim_body = sim_->findSimulationBody(body_item_);
193  if(!sim_body)
194  {
195  cnoid::MessageView::instance()->putln("[PosePublisherItem] SimulationBody not found", cnoid::MessageView::ERROR);
196  return;
197  }
198 
199  // Get Link
200  cnoid::DyLink * link = nullptr;
201  if(link_name_.empty())
202  {
203  link = static_cast<cnoid::DyBody *>(sim_body->body())->rootLink();
204  }
205  else
206  {
207  link = static_cast<cnoid::DyBody *>(sim_body->body())->link(link_name_);
208  }
209  if(!link)
210  {
211  cnoid::MessageView::instance()->putln("[PosePublisherItem] Link " + link_name_ + " not found",
212  cnoid::MessageView::ERROR);
213  return;
214  }
215 
216  // Publish message
217  ros::Time stamp_now = ros::Time::now();
218  // You need to use Ta() instead of T() to get correct rotation
219  // ref: https://github.com/s-nakaoka/choreonoid/commit/cefcfce0caddf94d9eef9c75277fc78e9fbd53b6
220  cnoid::Position pose = link->Ta();
221  if(output_tf_)
222  {
223  if(!tf_br_)
224  {
225  tf_br_ = std::make_shared<tf2_ros::TransformBroadcaster>();
226  }
227  geometry_msgs::TransformStamped msg;
228  msg.header.stamp = stamp_now;
229  msg.header.frame_id = frame_id_;
230  msg.child_frame_id = tf_child_frame_id_;
231  tf::vectorEigenToMsg(pose.translation(), msg.transform.translation);
232  tf::quaternionEigenToMsg(Eigen::Quaterniond(pose.rotation()), msg.transform.rotation);
233  tf_br_->sendTransform(msg);
234  }
235  else
236  {
237  geometry_msgs::PoseStamped pose_msg;
238  pose_msg.header.stamp = stamp_now;
239  pose_msg.header.frame_id = frame_id_;
240  tf::pointEigenToMsg(pose.translation(), pose_msg.pose.position);
241  tf::quaternionEigenToMsg(Eigen::Quaterniond(pose.rotation()), pose_msg.pose.orientation);
242  pose_pub_.publish(pose_msg);
243 
244  geometry_msgs::TwistStamped vel_msg;
245  vel_msg.header.stamp = stamp_now;
246  vel_msg.header.frame_id = frame_id_;
247  tf::vectorEigenToMsg(link->v(), vel_msg.twist.linear);
248  tf::vectorEigenToMsg(link->w(), vel_msg.twist.angular);
249  vel_pub_.publish(vel_msg);
250  }
251 }
252 
254 {
255  return std::max(static_cast<int>(1.0 / (pub_rate_ * sim_->worldTimeStep())), 1);
256 }
CnoidRosUtils::PosePublisherItem::vel_topic_name_
std::string vel_topic_name_
Definition: PosePublisherItem.h:80
CnoidRosUtils::PosePublisherItem::doDuplicate
virtual cnoid::Item * doDuplicate() const override
Definition: PosePublisherItem.cpp:53
CnoidRosUtils::PosePublisherItem::post_dynamics_func_id_
int post_dynamics_func_id_
Definition: PosePublisherItem.h:69
CnoidRosUtils::PosePublisherItem::initialized_
static bool initialized_
Definition: PosePublisherItem.h:35
CnoidRosUtils::PosePublisherItem::nh_
std::shared_ptr< ros::NodeHandle > nh_
Definition: PosePublisherItem.h:77
CnoidRosUtils::PosePublisherItem::frame_id_
std::string frame_id_
Definition: PosePublisherItem.h:78
CnoidRosUtils::PosePublisherItem
Plugin item to publish topics and broadcast TF of pose and velocity of the model.
Definition: PosePublisherItem.h:30
CnoidRosUtils::PosePublisherItem::hooked_sims_
std::set< std::string > hooked_sims_
Definition: PosePublisherItem.h:67
CnoidRosUtils::PosePublisherItem::output_tf_
bool output_tf_
Definition: PosePublisherItem.h:75
CnoidRosUtils::PosePublisherItem::store
virtual bool store(cnoid::Archive &archive) override
Definition: PosePublisherItem.cpp:77
CnoidRosUtils::PosePublisherItem::stop
void stop()
Definition: PosePublisherItem.cpp:173
CnoidRosUtils::PosePublisherItem::pub_skip_
int pub_skip_
Definition: PosePublisherItem.h:88
CnoidRosUtils::PosePublisherItem::vel_pub_
ros::Publisher vel_pub_
Definition: PosePublisherItem.h:84
CnoidRosUtils::PosePublisherItem::setup
void setup()
Definition: PosePublisherItem.cpp:103
CnoidRosUtils::PosePublisherItem::~PosePublisherItem
~PosePublisherItem()
Definition: PosePublisherItem.cpp:48
CnoidRosUtils::PosePublisherItem::body_item_
cnoid::BodyItem * body_item_
Definition: PosePublisherItem.h:71
CnoidRosUtils::PosePublisherItem::start
bool start()
Definition: PosePublisherItem.cpp:126
CnoidRosUtils::PosePublisherItem::pose_topic_name_
std::string pose_topic_name_
Definition: PosePublisherItem.h:79
CnoidRosUtils::PosePublisherItem::tf_child_frame_id_
std::string tf_child_frame_id_
Definition: PosePublisherItem.h:81
CnoidRosUtils::PosePublisherItem::onPostDynamics
void onPostDynamics()
Definition: PosePublisherItem.cpp:183
CnoidRosUtils::PosePublisherItem::getPubSkip
int getPubSkip() const
Definition: PosePublisherItem.cpp:253
CnoidRosUtils::PosePublisherItem::sim_cnt_
int sim_cnt_
Definition: PosePublisherItem.h:87
CnoidRosUtils::PosePublisherItem::pose_pub_
ros::Publisher pose_pub_
Definition: PosePublisherItem.h:83
CnoidRosUtils::PosePublisherItem::world_
cnoid::WorldItemPtr world_
Definition: PosePublisherItem.h:64
CnoidRosUtils::PosePublisherItem::tf_br_
std::shared_ptr< tf2_ros::TransformBroadcaster > tf_br_
Definition: PosePublisherItem.h:85
CnoidRosUtils::PosePublisherItem::PosePublisherItem
PosePublisherItem()
Definition: PosePublisherItem.cpp:35
CnoidRosUtils::PosePublisherItem::restore
virtual bool restore(const cnoid::Archive &archive) override
Definition: PosePublisherItem.cpp:90
CnoidRosUtils::PosePublisherItem::initialize
static void initialize(cnoid::ExtensionManager *ext)
Definition: PosePublisherItem.cpp:18
CnoidRosUtils::PosePublisherItem::doPutProperties
virtual void doPutProperties(cnoid::PutPropertyFunction &putProperty) override
Definition: PosePublisherItem.cpp:58
CnoidRosUtils::PosePublisherItem::pub_rate_
double pub_rate_
Definition: PosePublisherItem.h:82
CnoidRosUtils::PosePublisherItem::sim_
cnoid::SimulatorItemPtr sim_
Definition: PosePublisherItem.h:65
CnoidRosUtils::PosePublisherItem::link_name_
std::string link_name_
Definition: PosePublisherItem.h:73
PosePublisherItem.h
CnoidRosUtils
Definition: ClockPublisherItem.h:13