Skip to content

Conversation

@JBVAkshaya
Copy link

Changes Made

Multi-Robot Support

Tested on iron

Copy link
Member

@evan-palmer evan-palmer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Overall, this looks good @JBVAkshaya! Thanks for submitting this! This will be really helpful for folks. I've left some comments for improvements, but the general structure looks good!

EDIT: Also, you should be able to run clang-format to address these issues. The devcontainer runs that automatically

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This seems like it's mostly a copy of sitl.launch.yaml. Why not just modify that file?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For multi-robot purpose we have to instantiate gazebo world only once. The clock bridge has to be instantiated once as well. Hence, I had to break down to sitl.launch.yaml into two files. For multi-robot setup, the gazebo world is loaded separately (in blue_demos). I did not archive sitl.launch.yaml as others might be using this in current format. Their code will break.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This file is basically the same as ardusub.launch.yaml. Is there anything different about this and the modified SITL launch file that can't be integrated into the main launch files?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The param for sitl_multi.launch.yaml does not allow to set gazebo_world. Given we call sitl_mult.launch.yaml in ns_ardusub.launch.yaml I had to create a separate file.

ekf_origin_pub_ =
this->create_publisher<geographic_msgs::msg::GeoPointStamped>("/mavros/global_position/set_gp_origin", qos);

std::string topic_name_ = "/mavros/global_position/set_gp_origin";
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the _ suffix is reserved for member variables-

hardware_interface::return_type MavrosOdomSensor::read(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
if (rclcpp::ok()) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do we need to spin here?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am not exactly sure of the reason. But it does not work without spin. I got the solution from: https://github.com/PickNikRobotics/topic_based_ros2_control/blob/main/src/topic_based_system.cpp#L208


override_rc_pub_ =
node_->create_publisher<mavros_msgs::msg::OverrideRCIn>("mavros/rc/override", rclcpp::SystemDefaultsQoS());
std::string node_name_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

node_name_ is a bit confusing as the name here

if (namespace_ != "") {
RCLCPP_INFO( // NOLINT
rclcpp::get_logger("ThrusterHardware"), "Setting parameters for namespace: %s", namespace_.c_str());
node_name_ = namespace_ + "param/set_parameters";
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should probably split this into two variables for readability

Comment on lines +185 to +207
std::vector<std::string> ThrusterHardware::split(const std::string & str, char delimiter)
{
std::vector<std::string> tokens;
std::stringstream ss(str);
std::string token;
while (std::getline(ss, token, delimiter)) {
tokens.push_back(token);
}
return tokens;
}

std::string ThrusterHardware::concatenate_strings(const std::vector<std::string> & vec)
{
std::string result;
for (size_t i = 0; i < vec.size(); ++i) {
result += vec[i];
if (i != vec.size() - 1) {
result += "/";
}
}
return result;
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These don't need to be class functions. You can make these anonymous functions.

return tokens;
}

std::string ThrusterHardware::concatenate_strings(const std::vector<std::string> & vec)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there anything in the STL that you can use for this? You might be able to use the views API

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants