ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Generic robot parameter loading for multiple robots.

asked 2020-03-23 04:30:30 -0500

bob-ROS gravatar image

updated 2020-03-23 08:27:17 -0500

I currently have a package which subscribes to multiple robots. I wish to use a more generic solution where I use bind to generate the callback for each robot listed in the .yaml file. Example how I would like to parse the parameters:

Robot_parameters:
 name: Robot1 
  scan_topic_name: r2/scan
  sensor_frame: r1/lidar_link
  base_link_frame: r1/base_link

 name: Robot2
  scan_topic_name: r2/scan
  sensor_frame: r2/lidar_link
  base_link_frame: r2/base_link
 .
 .
 .
 name: a_robot_name
  scan_topic_name: topic_name
  sensor_frame: some_frame_name
  base_link_frame: another_frame_name

Looking for a good method to load these files. I can do this no-problem by loading a normal .txt file but I wanna do this in a "ROS" fashion by keeping it on the parameter server somehow. I wish to iterate over these parameters and bind these variables to callbacks for the N amount of robots.

edit retag flag offensive close merge delete

Comments

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-03-23 08:26:05 -0500

bob-ROS gravatar image

Made a functioning example:

#include <ros/ros.h>
#include <XmlRpcValue.h>
#include <sensor_msgs/LaserScan.h>
#include <boost/bind.hpp>

void callback(const sensor_msgs::LaserScan::ConstPtr& msg, std::string base_frame, std::string sensor_frame)
{
  ROS_INFO("Recieved scan on callback");
  ROS_INFO_STREAM("Base frame is: " << base_frame.c_str());
  ROS_INFO_STREAM("Sensor frame is: " <<sensor_frame.c_str());
}

int main( int argc, char** argv ){
 ros::init(argc, argv, "list_parameter_example_node");
 ros::NodeHandle nh;

 XmlRpc::XmlRpcValue robots;
 nh.getParam("robots", robots);
 ROS_ASSERT("failed to load parameters!" && robots.getType() == XmlRpc::XmlRpcValue::TypeStruct);
 std::vector<ros::Subscriber> sub_vector;
 for(XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = robots.begin(); it != robots.end(); ++it) {
   ROS_INFO_STREAM("Found robots: " << (std::string)(it->first) << " ==> " << robots[it->first]);
   ROS_INFO_STREAM("scan_topic_name: " << robots[it->first]["scan_topic_name"]);
   ROS_INFO_STREAM("Base_frame: " << robots[it->first]["base_frame"]);
   ROS_INFO_STREAM("sensor_frame: " << robots[it->first]["sensor_frame"]);

   sub_vector.push_back(nh.subscribe<sensor_msgs::LaserScan>(robots[it->first]["scan_topic_name"],1, boost::bind(&callback, _1, robots[it->first]["base_frame"],robots[it->first]["sensor_frame"])));

 }

 ros::Rate loop_rate(5); //5Hz

 while(ros::ok())
 {
   ros::spinOnce();
   loop_rate.sleep();
 }
}
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-03-23 04:30:30 -0500

Seen: 149 times

Last updated: Mar 23 '20