4 #include <boost/lambda/lambda.hpp> 8 #include "std_msgs/Header.h" 9 #include "std_msgs/String.h" 10 #include "jsk_topic_tools/List.h" 11 #include "jsk_topic_tools/Update.h" 24 std::string topic_name;
32 bool topic_with_header;
34 uint32_t last_seq_received;
35 uint32_t topic_received;
39 if ( advertised ==
false )
return;
42 if ( topic_with_header ==
true ) {
43 std_msgs::Header header;
44 uint8_t buf[msg->size()];
48 ((uint32_t *)buf)[0] = last_seq_received + topic_received;
50 ((uint32_t *)buf)[1] = tmp.
sec;
51 ((uint32_t *)buf)[2] = tmp.nsec;
75 using namespace boost::lambda;
78 s->topic_received = 0;
79 if ( s->advertised ==
false ) {
80 s->pub = msg->advertise(*g_node, s->topic_name+
string(
"_buffered"), 10, s->latched);
84 ROS_INFO_STREAM(
"advertised as " << s->topic_name+
string(
"_buffered") <<
" running at " << 1/(s->rate.toSec()) <<
"Hz");
89 std_msgs::Header header;
90 uint8_t buf[msg->size()];
93 header.seq = ((uint32_t *)buf)[0];
94 header.stamp.sec = ((uint32_t *)buf)[1];
95 header.stamp.nsec = ((uint32_t *)buf)[2];
99 ROS_INFO_STREAM(
" this message contains headers.. seq =" << header.seq <<
" stamp = " << header.stamp);
101 s->topic_with_header =
true;
102 s->last_seq_received = header.seq;
103 s->last_time_received = header.stamp;
111 s->timer = g_node->
createTimer(s->rate, &pub_info_t::publish, s);
122 double fixed_rate = 0.1;
125 nh.
param (
"fixed_rate", fixed_rate, 0.1);
126 ROS_INFO(
"use fixed rate = %f", fixed_rate);
129 double update_rate = 10;
131 nh.
param (
"update_rate", update_rate, 10.0);
132 ROS_INFO(
"use update rate = %f", update_rate);
135 double periodic_rate = 0.1;
138 nh.
param (
"periodic_rate", periodic_rate, 0.1);
139 ROS_INFO(
"use periodic rate = %f", periodic_rate);
144 nh.
param (
"latched", latched,
false);
151 bool use_service_p =
false;
152 std::vector<std::string> target_topics;
156 if (!nh.
getParam (
"topics", topics)) {
157 ROS_WARN(
"no ~topics is available, use service interface");
158 use_service_p =
true;
163 for (
int d = 0;
d < topics.
size(); ++
d) {
164 target_topics.push_back((std::string)(topics[
d]));
169 ROS_WARN(
"~topics mismatches type, it should be a list, use service interface");
170 use_service_p =
true;
176 target_topics.clear();
180 jsk_topic_tools::List::Request req;
181 jsk_topic_tools::List::Response res;
183 while ( sc_list.
call(req, res) ==
false) {
188 for(vector<std::string>::iterator it = res.topic_names.begin(); it != res.topic_names.end(); ++it) {
189 target_topics.push_back(*it);
191 ROS_INFO_STREAM(
"calling /list has done.. found " << res.topic_names.size() <<
" topics to publish");
193 for(
size_t i = 0; i < target_topics.size(); i++) {
195 pub_info->topic_name = target_topics[i];
199 pub_info->latched = latched;
200 pub_info->advertised =
false;
201 pub_info->topic_with_header =
false;
202 ROS_INFO_STREAM(
"subscribe " << pub_info->topic_name+
string(
"_update"));
205 g_pubs.push_back(pub_info);
211 bool use_service =
true;
212 nh.
param(
"use_service", use_service,
true);
219 pub_update = n.
advertise<std_msgs::String>(
"/update", 1);
223 for (list<pub_info_ref>::iterator it =
g_pubs.begin();
226 jsk_topic_tools::Update::Request req;
227 jsk_topic_tools::Update::Response res;
228 req.topic_name = (*it)->topic_name;
231 sc_update.
call(req, res);
232 ROS_INFO_STREAM(
"sending request for periodic rate publish topic:" << req.topic_name <<
" rate:" << req.periodic_rate);
238 for (list<pub_info_ref>::iterator it =
g_pubs.begin();
243 jsk_topic_tools::Update::Request req;
244 jsk_topic_tools::Update::Response res;
245 req.topic_name = (*it)->topic_name;
246 if ( sc_update.
call(req, res) == false ) {
247 ROS_ERROR_STREAM(
"calling /update (" << req.topic_name <<
") fails, retry...");
248 sc_update = n.
serviceClient<jsk_topic_tools::Update>(string(
"/update"),
true);
253 ROS_INFO_STREAM(
"calling /update " << req.topic_name <<
" .. " << res.rate);
257 std_msgs::String
msg;
258 msg.data = (*it)->topic_name;
259 pub_update.publish(msg);
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
boost::shared_ptr< pub_info_t > pub_info_ref
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
Type const & getType() const
int main(int argc, char **argv)
static list< pub_info_ref > g_pubs
void in_cb(const boost::shared_ptr< ShapeShifter const > &msg, boost::shared_ptr< pub_info_t > s)
static bool use_periodic_rate
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static ros::NodeHandle * g_node
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
static bool use_fixed_rate
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)