First time here? Check out the FAQ!


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

Revision history [back]

click to hide/show revision 1
initial version

I am confused about the error you reported, as it is shown that the error is coming from the robot_localization package. Basically, ros::param should be a part of the ROS core thus should be unrelated to the robot_localization package.

Nevertheless, below is what I tried and found working:

#include <ros/ros.h>

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

  // define a shorthand notation
  using BoolVector = std::vector<bool>;

  BoolVector odomConfig;

  // define a handy lambda funciton
  const auto printConfig = [&odomConfig]() {
    std::string configStr = "";
    for (const auto& item : odomConfig)
      configStr += item ? "true " : "false ";
    ROS_INFO("odom_config[%zu] items:[%s]", odomConfig.size(), configStr.c_str());
  };

  // no default
  nh.getParam("odom_config", odomConfig);
  printConfig();

  // with default
  nh.param("odom_config", odomConfig,
           { false, false, false, false, false, false, true, true, true, false, false, false, false, false, false });
  printConfig();

  ros::param::param("odom_config", odomConfig,
                    { false, false, false, false, false, false, true, true, true, false, false, false, false, false });
  printConfig();

  ros::param::param<BoolVector>("odom_config", odomConfig, { false, true, true, true, false, false });
  printConfig();

  return 0;
}

This is what I saw while running it:

$ rosrun beginner_tutorials talker_rosparam 
[ INFO] [1664457912.188430402]: odom_config[0] items:[]
[ INFO] [1664457912.189091735]: odom_config[15] items:[false false false false false false true true true false false false false false false ]
[ INFO] [1664457912.189296018]: odom_config[14] items:[false false false false false false true true true false false false false false ]
[ INFO] [1664457912.189495235]: odom_config[6] items:[false true true true false false ]

Last but not least, please avoid using std::vector<bool> and redefine BoolVector based on the alternatives mentioned by @ljaniec

click to hide/show revision 2
No.2 Revision

I am confused about the error you reported, as it is shown that the error is coming from the robot_localization package. Basically, ros::param should be a part of the ROS core thus should be unrelated to the robot_localization package.

Nevertheless, below is what I tried and found working:

#include <ros/ros.h>

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

  // define a shorthand notation
  using BoolVector = std::vector<bool>;

  BoolVector odomConfig;

  // define a handy lambda funciton
  const auto printConfig = [&odomConfig]() {
    std::string configStr = "";
    for (const auto& item : odomConfig)
      configStr += item ? "true " : "false ";
    ROS_INFO("odom_config[%zu] items:[%s]", odomConfig.size(), configStr.c_str());
  };

  // no default
  nh.getParam("odom_config", odomConfig);
  printConfig();

  // with default
  nh.param("odom_config", odomConfig,
           { false, false, false, false, false, false, true, true, true, false, false, false, false, false, false });
  printConfig();

  ros::param::param("odom_config", odomConfig,
                    { false, false, false, false, false, false, true, true, true, false, false, false, false, false });
  printConfig();

  ros::param::param<BoolVector>("odom_config", odomConfig, { false, true, true, true, false, false });
  printConfig();

  // set as ros param
  nh.setParam("odom_config", odomConfig);

  // no default but this time, we should be getting it from parameter server
  nh.getParam("odom_config", odomConfig);
  printConfig();

  return 0;
}

This is what I saw while running it:

$ rosrun beginner_tutorials talker_rosparam 
[ INFO] [1664457912.188430402]: odom_config[0] items:[]
[ INFO] [1664457912.189091735]: odom_config[15] items:[false false false false false false true true true false false false false false false ]
[ INFO] [1664457912.189296018]: odom_config[14] items:[false false false false false false true true true false false false false false ]
[ INFO] [1664457912.189495235]: odom_config[6] items:[false true true true false false ]
[ INFO] [1664459025.189954825]: odom_config[6] items:[false true true true false false ]

I can also get it from the parameter server as shown below:

$ rosparam get /odom_config
- false
- true
- true
- true
- false
- false

Last but not least, please avoid using std::vector<bool> and redefine BoolVector based on the alternatives mentioned by @ljaniec

click to hide/show revision 3
No.3 Revision

I am confused suspect about the error you reported, as it is shown that the error is coming from the robot_localization package. Basically, However, ros::param should be is a part of the ROS core thus should be unrelated to the robot_localization package.

Nevertheless, below is what I tried and found working:

#include <ros/ros.h>

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

  // define a shorthand notation
  using BoolVector = std::vector<bool>;

  BoolVector odomConfig;

  // define a handy lambda funciton
  const auto printConfig = [&odomConfig]() {
    std::string configStr = "";
    for (const auto& item : odomConfig)
      configStr += item ? "true " : "false ";
    ROS_INFO("odom_config[%zu] items:[%s]", odomConfig.size(), configStr.c_str());
  };

  // no default
  nh.getParam("odom_config", odomConfig);
  printConfig();

  // with default
  nh.param("odom_config", odomConfig,
           { false, false, false, false, false, false, true, true, true, false, false, false, false, false, false });
  printConfig();

  ros::param::param("odom_config", odomConfig,
                    { false, false, false, false, false, false, true, true, true, false, false, false, false, false });
  printConfig();

  ros::param::param<BoolVector>("odom_config", odomConfig, { false, true, true, true, false, false });
  printConfig();

  // set as ros param
  nh.setParam("odom_config", odomConfig);

  // no default but this time, we should be getting it from parameter server
  nh.getParam("odom_config", odomConfig);
  printConfig();

  return 0;
}

This is what I saw while running it:

$ rosrun beginner_tutorials talker_rosparam 
[ INFO] [1664457912.188430402]: odom_config[0] items:[]
[ INFO] [1664457912.189091735]: odom_config[15] items:[false false false false false false true true true false false false false false false ]
[ INFO] [1664457912.189296018]: odom_config[14] items:[false false false false false false true true true false false false false false ]
[ INFO] [1664457912.189495235]: odom_config[6] items:[false true true true false false ]
[ INFO] [1664459025.189954825]: odom_config[6] items:[false true true true false false ]

I can also get it from the parameter server as shown below:

$ rosparam get /odom_config
- false
- true
- true
- true
- false
- false

Last but not least, please avoid using std::vector<bool> and redefine BoolVector based on the alternatives mentioned by @ljaniec