3 #include <cnoid/BodyItem>
4 #include <cnoid/DyBody>
5 #include <cnoid/ItemManager>
6 #include <cnoid/MessageView>
7 #include <cnoid/PutPropertyFunction>
8 #include <cnoid/RootItem>
10 #include <geometry_msgs/PoseStamped.h>
11 #include <geometry_msgs/TransformStamped.h>
12 #include <geometry_msgs/TwistStamped.h>
22 if(!ros::isInitialized())
24 ros::init(argc, argv,
"choreonoid_ros");
29 ext->itemManager().registerClass<
PosePublisherItem>(
"CnoidRosUtils::PosePublisherItem");
60 cnoid::Item::doPutProperties(putProperty);
66 putProperty(
"Publish rate",
pub_rate_, [&](
const double & pub_rate) {
67 pub_rate_ = std::min(std::max(pub_rate, 1e-1), 1e3);
82 archive.write(
"Velocity topic name (only for topic output)",
vel_topic_name_);
95 archive.read(
"Velocity topic name (only for topic output)",
vel_topic_name_);
106 world_ = this->findOwnerItem<cnoid::WorldItem>();
114 for(cnoid::Item * child =
world_->childItem(); child; child = child->nextItem())
116 cnoid::SimulatorItemPtr sim =
dynamic_cast<cnoid::SimulatorItem *
>(child);
117 if(sim && !sim->isRunning() && !
hooked_sims_.count(sim->name()))
129 sim_ = cnoid::SimulatorItem::findActiveSimulatorItemFor(
this);
132 cnoid::MessageView::instance()->putln(
"[PosePublisherItem] SimulatorItem not found", cnoid::MessageView::ERROR);
137 body_item_ = this->findOwnerItem<cnoid::BodyItem>();
140 cnoid::MessageView::instance()->putln(
"[PosePublisherItem] Owner BodyItem not found", cnoid::MessageView::ERROR);
145 nh_ = std::make_shared<ros::NodeHandle>();
192 cnoid::SimulationBody * sim_body =
sim_->findSimulationBody(
body_item_);
195 cnoid::MessageView::instance()->putln(
"[PosePublisherItem] SimulationBody not found", cnoid::MessageView::ERROR);
200 cnoid::DyLink * link =
nullptr;
203 link =
static_cast<cnoid::DyBody *
>(sim_body->body())->rootLink();
207 link =
static_cast<cnoid::DyBody *
>(sim_body->body())->link(
link_name_);
211 cnoid::MessageView::instance()->putln(
"[PosePublisherItem] Link " +
link_name_ +
" not found",
212 cnoid::MessageView::ERROR);
217 ros::Time stamp_now = ros::Time::now();
220 cnoid::Position pose = link->Ta();
225 tf_br_ = std::make_shared<tf2_ros::TransformBroadcaster>();
227 geometry_msgs::TransformStamped msg;
228 msg.header.stamp = stamp_now;
231 tf::vectorEigenToMsg(pose.translation(), msg.transform.translation);
232 tf::quaternionEigenToMsg(Eigen::Quaterniond(pose.rotation()), msg.transform.rotation);
233 tf_br_->sendTransform(msg);
237 geometry_msgs::PoseStamped pose_msg;
238 pose_msg.header.stamp = stamp_now;
240 tf::pointEigenToMsg(pose.translation(), pose_msg.pose.position);
241 tf::quaternionEigenToMsg(Eigen::Quaterniond(pose.rotation()), pose_msg.pose.orientation);
244 geometry_msgs::TwistStamped vel_msg;
245 vel_msg.header.stamp = stamp_now;
247 tf::vectorEigenToMsg(link->v(), vel_msg.twist.linear);
248 tf::vectorEigenToMsg(link->w(), vel_msg.twist.angular);
255 return std::max(
static_cast<int>(1.0 / (
pub_rate_ *
sim_->worldTimeStep())), 1);