3 #include <cnoid/BodyItem>
4 #include <cnoid/ItemManager>
5 #include <cnoid/MessageView>
6 #include <cnoid/PutPropertyFunction>
7 #include <cnoid/RootItem>
17 if(!ros::isInitialized())
19 ros::init(argc, argv,
"choreonoid_ros");
24 ext->itemManager().registerClass<
ClockPublisherItem>(
"CnoidRosUtils::ClockPublisherItem");
55 cnoid::Item::doPutProperties(putProperty);
57 putProperty(
"Publish rate",
pub_rate_, [&](
const double & pub_rate) {
58 pub_rate_ = std::min(std::max(pub_rate, 1e-1), 1e3);
89 world_ = this->findOwnerItem<cnoid::WorldItem>();
97 for(Item * child =
world_->childItem(); child; child = child->nextItem())
99 cnoid::SimulatorItemPtr sim =
dynamic_cast<cnoid::SimulatorItem *
>(child);
100 if(sim && !sim->isRunning() && !
hooked_sims_.count(sim->name()))
112 sim_ = cnoid::SimulatorItem::findActiveSimulatorItemFor(
this);
115 cnoid::MessageView::instance()->putln(
"[ClockPublisherItem] SimulatorItem not found", cnoid::MessageView::ERROR);
120 nh_ = std::make_shared<ros::NodeHandle>();
156 rosgraph_msgs::Clock msg;
157 msg.clock.fromSec(
sim_->currentTime());
163 return std::max(
static_cast<int>(1.0 / (
pub_rate_ *
sim_->worldTimeStep())), 1);