robot_localization: navsat_transform_node runtime error
Hello all.
I have cloned the most up to date version of the robotlocalization package from the GitHub repository. I experience a runtime error as I attempt to run the navsattransform_node. This is the output:
terminate called after throwing an instance of 'rclcpp::exceptions::ParameterAlreadyDeclaredException'
what(): parameter 'broadcast_utm_transform' has already been declared
- Operating System:
Ubuntu 20.04.2 LTS
Installation type:
Source
Version or commit hash:
3.1.1
Steps to reproduce issue:
git clone -b foxy-devel https://github.com/cra-ros-pkg/robot_localization.git
colcon build --packages-select robot_localization
source install/setup.bash
ros2 run robotlocalization navsattransform_node
Expected behavior
The node will run without a runtime error
Actual behavior
Node crashes with the following console output:
terminate called after throwing an instance of 'rclcpp::exceptions::ParameterAlreadyDeclaredException'
what(): parameter 'broadcastutmtransform' has already been declared
Any help on this matter would greatly appreciated.
Asked by yefty on 2021-05-13 12:03:19 UTC
Answers
Have you opened this up as an issue on the github page for this package? What I am about to explain is more properly placed there.
The issue is on lines 110-120 of navsat_transform.cpp
broadcast_cartesian_transform_ =
this->declare_parameter("broadcast_utm_transform", broadcast_cartesian_transform_);
if (broadcast_cartesian_transform_) {
RCLCPP_WARN(
this->get_logger(), "Parameter 'broadcast_utm_transform' has been deprecated. "
"Please use 'broadcast_cartesian_transform' instead.");
} else {
broadcast_cartesian_transform_ =
this->declare_parameter("broadcast_utm_transform", broadcast_cartesian_transform_);
}
We can see that if the broadcast_utm_transform
parameter is false, it will be declared on both the first statement and in the else branch.
If I had to guess on the intent of the code, the else branch should look more like this:
} else {
broadcast_cartesian_transform_ =
this->declare_parameter("broadcast_cartesian_transform", broadcast_cartesian_transform_);
}
(the name of the parameter should be different)
To jump passed this without modifying code, pass it true for broadcast_utm_transform
parameter with:
ros2 run robot_localization navsat_transform_node --ros-args -p broadcast_utm_transform:=true
Please either open an issue on the github page, or let me know if you are not going to so I can.
Hope this helps!
Asked by djchopp on 2021-05-14 11:48:18 UTC
Comments
Thanks for the descriptive answer! Works like a charm and makes perfect sense. Originally I was just going to file a bug report but as I was going to, this message popped up:
<!-- All questions should be directed to answers.ros.org. Similarly, before filing a bug report, please check for solutions to your issue on answers.ros.org. -->.
So I was just making sure I was covering my bases first. Your answer has convinced me to file a bug report. Thank you very much.
Asked by yefty on 2021-05-14 16:20:02 UTC
Comments