Skip to content

Commit

Permalink
fix missing linters; tune tutorial params
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Sep 24, 2024
1 parent a2bb49f commit ea454bc
Show file tree
Hide file tree
Showing 6 changed files with 53 additions and 8 deletions.
2 changes: 0 additions & 2 deletions mrpt_msgs_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -97,8 +97,6 @@ install(

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_copyright REQUIRED)
find_package(ament_cmake_cpplint REQUIRED)
find_package(ament_cmake_lint_cmake REQUIRED)
find_package(ament_cmake_xmllint REQUIRED)

Expand Down
6 changes: 5 additions & 1 deletion mrpt_tps_astar_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ Uses A* over a SE(2) lattice and PTGs to sample collision-free paths. The implem

### ROS 2 parameters

* `topic_wp_seq_pub` (Default: `/waypoints`) Desired name of the topic in which to publish the calculated paths.

* `topic_goal_sub`: The name of the topic to subscribe for goal poses (`geometry_msgs/PoseStamped`).

* `show_gui`: Shows its own MRPT GUI with the planned paths.
Expand All @@ -37,11 +39,13 @@ Uses A* over a SE(2) lattice and PTGs to sample collision-free paths. The implem

* `topic_obstacle_points_sub`: One or more (comma separated) topic names to subscribe for obstacle points.


### Subscribed topics
* xxx

### Published topics
* `` (`mrpt_msgs::msg::WaypointSequence`)
* `<topic_wp_seq_pub>` (Default: `/waypoints`) (`mrpt_msgs::msg::WaypointSequence`): Calculated trajectory, in mrpt_msgs format with complete details for each waypoints.
* `<topic_wp_seq_pub>_path` (Default: `/waypoints_path`) (`nav_msgs::msg::Path`): Calculated trajectory, as `nav_msgs::Path`. Mostly useful for visualization only.

### Services

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@ maxCost: 15.0

useAverageOfPath: false

maxRadiusFromRobot: 25.0 # [meters]
maxRadiusFromRobot: 50.0 # [meters]

15 changes: 15 additions & 0 deletions mrpt_tps_astar_planner/src/mrpt_tps_astar_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <mutex>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <nav_msgs/msg/path.hpp>
#include <optional>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -108,6 +109,7 @@ class TPS_Astar_Planner_Node : public rclcpp::Node

/// Publisher for waypoint sequence
rclcpp::Publisher<mrpt_msgs::msg::WaypointSequence>::SharedPtr pub_wp_seq_;
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr pub_wp_path_seq_;

// tf2 buffer and listener
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
Expand Down Expand Up @@ -342,6 +344,8 @@ TPS_Astar_Planner_Node::TPS_Astar_Planner_Node() : rclcpp::Node(NODE_NAME)
// Init ROS publishers:
// -----------------------
pub_wp_seq_ = this->create_publisher<mrpt_msgs::msg::WaypointSequence>(topic_wp_seq_pub_, qos);
pub_wp_path_seq_ =
this->create_publisher<nav_msgs::msg::Path>(topic_wp_seq_pub_ + "_path"s, qos);

// Init services:
// --------------------------
Expand Down Expand Up @@ -595,6 +599,17 @@ void TPS_Astar_Planner_Node::update_obstacles(
void TPS_Astar_Planner_Node::publish_waypoint_sequence(const mrpt_msgs::msg::WaypointSequence& wps)
{
pub_wp_seq_->publish(wps);

// As Path too:
nav_msgs::msg::Path p;
p.header = wps.header;
for (const auto& w : wps.waypoints)
{
auto& q = p.poses.emplace_back();
q.header = p.header; // Add actual timestamp per path pose??
q.pose = w.target;
}
pub_wp_path_seq_->publish(p);
}

void TPS_Astar_Planner_Node::init_3d_debug()
Expand Down
4 changes: 2 additions & 2 deletions mrpt_tutorials/launch/demo_astar_planner_gridmap.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ def generate_launch_description():
'tps_astar_planner.launch.py')]),
launch_arguments={
'topic_goal_sub': '/goal_pose',
'show_gui': 'True',
'show_gui': 'False',
'topic_obstacles_gridmap_sub': '/mrpt_map/map_gridmap',
'topic_static_maps': '/mrpt_map/map_gridmap',
'topic_wp_seq_pub': '/waypoints',
Expand All @@ -49,7 +49,7 @@ def generate_launch_description():
{
"world_file": os.path.join(tutsDir, 'mvsim', 'demo_world2.world.xml'),
"do_fake_localization": True,
"show_gui": True,
"headless": True,
}]
)

Expand Down
32 changes: 30 additions & 2 deletions mrpt_tutorials/rviz2/gridmap.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -210,6 +210,34 @@ Visualization Manager:
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz_default_plugins/Path
Color: 25; 255; 0
Enabled: true
Head Diameter: 0.30000001192092896
Head Length: 0.10000000149011612
Length: 0.30000001192092896
Line Style: Lines
Line Width: 0.029999999329447746
Name: Path
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 255; 85; 255
Pose Style: Axes
Radius: 0.029999999329447746
Shaft Diameter: 0.10000000149011612
Shaft Length: 0.10000000149011612
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /waypoints_path
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -265,7 +293,7 @@ Visualization Manager:
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Scale: 10.372156143188477
Scale: 11.861957550048828
Target Frame: <Fixed Frame>
Value: TopDownOrtho (rviz_default_plugins)
X: 43.450077056884766
Expand All @@ -288,4 +316,4 @@ Window Geometry:
collapsed: false
Width: 1850
X: 70
Y: 534
Y: 27

0 comments on commit ea454bc

Please sign in to comment.