Skip to content
This repository has been archived by the owner on Aug 1, 2024. It is now read-only.

improve avoidance node to use ROS2 #611

Open
wants to merge 3 commits into
base: ros2
Choose a base branch
from
Open

improve avoidance node to use ROS2 #611

wants to merge 3 commits into from

Conversation

ldg810
Copy link
Contributor

@ldg810 ldg810 commented Nov 27, 2020

I am working on to use PX4-Avoidance global_planner in ROS2 environment.

Until now, I succeed with subscribing a topic(VehicleLocalPosition) in ROS2 environment.

The avoidance node should be changed to the following reasons.

  • In current form, the two avoidance nodes(avoidance_node_cmd, avoidance_node_status) spinning and it stuck with executor.join() function. Thus, I made thread/related variables as global variable to make it spin in the background.
  • tf2::fromMsg usage was fault. I change the order of input parameters but I failed to use "tf2::fromMsg(tf_earlier.transform.translation, tf_earlier_translation);". In tf2 documentation, there is a declaration about geometry_msgs::msg::Vector3 and tf2::Vector3 but it is not working.. So I changed it to "tf_earlier_translation.setValue(tf_earlier.transform.translation.x, tf_earlier.transform.translation.y, tf_earlier.transform.translation.z);" as directly assign Vector3 values to tf_earlier_translation. (Please give a comment about this)

The message type of mavros and px4_msgs in ROS2 is quite different so I thinks its little bit hard work to porting global_planner to ROS2 environment but I will try to solve it.

Declare loop thread as global variable and node shared pointers to execute spinning in the background
modify tf2::fromMsg usage
@Jaeyoung-Lim
Copy link
Member

Jaeyoung-Lim commented Nov 27, 2020

@TSC21 This might be interesting for you

@TSC21
Copy link
Member

TSC21 commented Nov 27, 2020

@TSC21 This might be interesting for you

Absolutely and I totally support the effort of continuing pushing this forward. There's still things to get wrapped up and I was just focused on the local planner.

@ldg810 what ROS2 version are you testing this against?

@ldg810
Copy link
Contributor Author

ldg810 commented Nov 27, 2020

@TSC21 This might be interesting for you

Absolutely and I totally support the effort of continuing pushing this forward. There's still things to get wrapped up and I was just focused on the local planner.

@ldg810 what ROS2 version are you testing this against?

Thank you for your comment.

Now, I am using ros2 dashing and using px4_sitl_rtps for px4 firmware.

I will also summarize my simulation environment to readme file.

@TSC21
Copy link
Member

TSC21 commented Nov 27, 2020

@TSC21 This might be interesting for you

Absolutely and I totally support the effort of continuing pushing this forward. There's still things to get wrapped up and I was just focused on the local planner.
@ldg810 what ROS2 version are you testing this against?

Thank you for your comment.

Now, I am using ros2 dashing and using px4_sitl_rtps for px4 firmware.

I will also summarize my simulation environment to readme file.

Are you able to use ROS2 Foxy instead? We are currently aiming for that distro as LTS for the microRTPS bridge.

@ldg810
Copy link
Contributor Author

ldg810 commented Nov 27, 2020

@TSC21 This might be interesting for you

Absolutely and I totally support the effort of continuing pushing this forward. There's still things to get wrapped up and I was just focused on the local planner.
@ldg810 what ROS2 version are you testing this against?

Thank you for your comment.

Now, I am using ros2 dashing and using px4_sitl_rtps for px4 firmware.

I will also summarize my simulation environment to readme file.

Are you able to use ROS2 Foxy instead? We are currently aiming for that distro as LTS for the microRTPS bridge.

Yes, no problem to use foxy. I made Dockerfile for my environment so changing version is not problem.

I will test the planner in foxy environment.

ldg810 and others added 2 commits November 27, 2020 21:12
remove unnecessary blank

Co-authored-by: Nuno Marques <n.marques21@hotmail.com>
To correctly count the size of obst_avoid.waypoints, sizeof() should be changed to .size() function.
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants