cnoid_ros_utils
ClockPublisherItem.cpp
Go to the documentation of this file.
1 /* Author: Masaki Murooka */
2 
3 #include <cnoid/BodyItem>
4 #include <cnoid/ItemManager>
5 #include <cnoid/MessageView>
6 #include <cnoid/PutPropertyFunction>
7 #include <cnoid/RootItem>
8 
9 #include "ClockPublisherItem.h"
10 
11 using namespace CnoidRosUtils;
12 
13 void ClockPublisherItem::initialize(cnoid::ExtensionManager * ext)
14 {
15  int argc = 0;
16  char ** argv;
17  if(!ros::isInitialized())
18  {
19  ros::init(argc, argv, "choreonoid_ros");
20  }
21 
22  if(!initialized_)
23  {
24  ext->itemManager().registerClass<ClockPublisherItem>("CnoidRosUtils::ClockPublisherItem");
25  ext->itemManager().addCreationPanel<ClockPublisherItem>();
26  initialized_ = true;
27  }
28 }
29 
31 {
32  cnoid::RootItem::instance()->sigTreeChanged().connect(boost::bind(&ClockPublisherItem::setup, this));
33 }
34 
36 {
37  cnoid::RootItem::instance()->sigTreeChanged().connect(boost::bind(&ClockPublisherItem::setup, this));
38  hooked_sims_.clear();
40  sim_cnt_ = 0;
41 }
42 
44 {
45  stop();
46 }
47 
48 cnoid::Item * ClockPublisherItem::doDuplicate() const
49 {
50  return new ClockPublisherItem(*this);
51 }
52 
53 void ClockPublisherItem::doPutProperties(cnoid::PutPropertyFunction & putProperty)
54 {
55  cnoid::Item::doPutProperties(putProperty);
56  putProperty("Clock topic name", clock_topic_name_, cnoid::changeProperty(clock_topic_name_));
57  putProperty("Publish rate", pub_rate_, [&](const double & pub_rate) {
58  pub_rate_ = std::min(std::max(pub_rate, 1e-1), 1e3);
59  if(sim_)
60  {
62  }
63  return true;
64  });
65  putProperty("Set use_sim_time", use_sim_time_, cnoid::changeProperty(use_sim_time_));
66 }
67 
68 bool ClockPublisherItem::store(cnoid::Archive & archive)
69 {
70  archive.write("Clock topic name", clock_topic_name_);
71  archive.write("Publish rate", pub_rate_);
72  archive.write("Set use_sim_time", use_sim_time_);
73 
74  return true;
75 }
76 
77 bool ClockPublisherItem::restore(const cnoid::Archive & archive)
78 {
79  archive.read("Clock topic name", clock_topic_name_);
80  archive.read("Publish rate", pub_rate_);
81  archive.read("Set use_sim_time", use_sim_time_);
82 
83  return true;
84 }
85 
87 {
88  // Get WorldItem
89  world_ = this->findOwnerItem<cnoid::WorldItem>();
90  if(!world_)
91  {
92  // cnoid::MessageView::instance()->putln("[ClockPublisherItem] WorldItem not found", cnoid::MessageView::ERROR);
93  return;
94  }
95 
96  // Set hook functions for simulation start and stop
97  for(Item * child = world_->childItem(); child; child = child->nextItem())
98  {
99  cnoid::SimulatorItemPtr sim = dynamic_cast<cnoid::SimulatorItem *>(child);
100  if(sim && !sim->isRunning() && !hooked_sims_.count(sim->name()))
101  {
102  sim->sigSimulationStarted().connect(std::bind(&ClockPublisherItem::start, this));
103  sim->sigSimulationFinished().connect(std::bind(&ClockPublisherItem::stop, this));
104  hooked_sims_.insert(sim->name());
105  }
106  }
107 }
108 
110 {
111  // Get SimulatorItem
112  sim_ = cnoid::SimulatorItem::findActiveSimulatorItemFor(this);
113  if(!sim_)
114  {
115  cnoid::MessageView::instance()->putln("[ClockPublisherItem] SimulatorItem not found", cnoid::MessageView::ERROR);
116  return false;
117  }
118 
119  // Setup ROS
120  nh_ = std::make_shared<ros::NodeHandle>();
121 
122  if(clock_topic_name_.empty())
123  {
124  clock_topic_name_ = "/clock";
125  }
126  clock_pub_ = nh_->advertise<rosgraph_msgs::Clock>(clock_topic_name_, 1);
127  pub_skip_ = getPubSkip();
128 
129  nh_->setParam("/use_sim_time", use_sim_time_);
130 
131  // Add postDynamicsFunction
132  post_dynamics_func_id_ = sim_->addPostDynamicsFunction(std::bind(&ClockPublisherItem::onPostDynamics, this));
133 
134  return true;
135 }
136 
138 {
139  // Remove postDynamicsFunction
140  if(post_dynamics_func_id_ != -1)
141  {
142  sim_->removePostDynamicsFunction(post_dynamics_func_id_);
144  }
145 }
146 
148 {
149  sim_cnt_++;
150  if(sim_cnt_ % pub_skip_ != 0)
151  {
152  return;
153  }
154 
155  // Publish a message
156  rosgraph_msgs::Clock msg;
157  msg.clock.fromSec(sim_->currentTime());
158  clock_pub_.publish(msg);
159 }
160 
162 {
163  return std::max(static_cast<int>(1.0 / (pub_rate_ * sim_->worldTimeStep())), 1);
164 }
CnoidRosUtils::ClockPublisherItem::pub_skip_
int pub_skip_
Definition: ClockPublisherItem.h:70
CnoidRosUtils::ClockPublisherItem::doPutProperties
virtual void doPutProperties(cnoid::PutPropertyFunction &putProperty) override
Definition: ClockPublisherItem.cpp:53
CnoidRosUtils::ClockPublisherItem::getPubSkip
int getPubSkip() const
Definition: ClockPublisherItem.cpp:161
CnoidRosUtils::ClockPublisherItem::onPostDynamics
void onPostDynamics()
Definition: ClockPublisherItem.cpp:147
CnoidRosUtils::ClockPublisherItem::ClockPublisherItem
ClockPublisherItem()
Definition: ClockPublisherItem.cpp:30
CnoidRosUtils::ClockPublisherItem::start
bool start()
Definition: ClockPublisherItem.cpp:109
CnoidRosUtils::ClockPublisherItem::sim_
cnoid::SimulatorItemPtr sim_
Definition: ClockPublisherItem.h:57
CnoidRosUtils::ClockPublisherItem::use_sim_time_
bool use_sim_time_
Definition: ClockPublisherItem.h:67
CnoidRosUtils::ClockPublisherItem::clock_pub_
ros::Publisher clock_pub_
Definition: ClockPublisherItem.h:66
CnoidRosUtils::ClockPublisherItem::world_
cnoid::WorldItemPtr world_
Definition: ClockPublisherItem.h:56
CnoidRosUtils::ClockPublisherItem::clock_topic_name_
std::string clock_topic_name_
Definition: ClockPublisherItem.h:64
CnoidRosUtils::ClockPublisherItem::stop
void stop()
Definition: ClockPublisherItem.cpp:137
CnoidRosUtils::ClockPublisherItem::~ClockPublisherItem
~ClockPublisherItem()
Definition: ClockPublisherItem.cpp:43
ClockPublisherItem.h
CnoidRosUtils::ClockPublisherItem::nh_
std::shared_ptr< ros::NodeHandle > nh_
Definition: ClockPublisherItem.h:63
CnoidRosUtils::ClockPublisherItem
Plugin item to publish clock topic.
Definition: ClockPublisherItem.h:22
CnoidRosUtils::ClockPublisherItem::sim_cnt_
int sim_cnt_
Definition: ClockPublisherItem.h:69
CnoidRosUtils::ClockPublisherItem::post_dynamics_func_id_
int post_dynamics_func_id_
Definition: ClockPublisherItem.h:61
CnoidRosUtils::ClockPublisherItem::hooked_sims_
std::set< std::string > hooked_sims_
Definition: ClockPublisherItem.h:59
CnoidRosUtils::ClockPublisherItem::restore
virtual bool restore(const cnoid::Archive &archive) override
Definition: ClockPublisherItem.cpp:77
CnoidRosUtils::ClockPublisherItem::setup
void setup()
Definition: ClockPublisherItem.cpp:86
CnoidRosUtils
Definition: ClockPublisherItem.h:13
CnoidRosUtils::ClockPublisherItem::store
virtual bool store(cnoid::Archive &archive) override
Definition: ClockPublisherItem.cpp:68
CnoidRosUtils::ClockPublisherItem::initialize
static void initialize(cnoid::ExtensionManager *ext)
Definition: ClockPublisherItem.cpp:13
CnoidRosUtils::ClockPublisherItem::doDuplicate
virtual cnoid::Item * doDuplicate() const override
Definition: ClockPublisherItem.cpp:48
CnoidRosUtils::ClockPublisherItem::pub_rate_
double pub_rate_
Definition: ClockPublisherItem.h:65
CnoidRosUtils::ClockPublisherItem::initialized_
static bool initialized_
Definition: ClockPublisherItem.h:27