Skip to content

Commit ff3392d

Browse files
mikefergusonSteveMacenski
authored andcommitted
publish motion target as pose (#4839)
Signed-off-by: Michael Ferguson <[email protected]>
1 parent 6f4d597 commit ff3392d

File tree

5 files changed

+3
-59
lines changed

5 files changed

+3
-59
lines changed

nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ class GracefulController : public nav2_core::Controller
173173

174174
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_plan_pub_;
175175
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> local_plan_pub_;
176-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
176+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseStamped>>
177177
motion_target_pub_;
178178
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::Marker>>
179179
slowdown_pub_;

nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp

Lines changed: 0 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -15,22 +15,11 @@
1515
#ifndef NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_
1616
#define NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_
1717

18-
#include "geometry_msgs/msg/point_stamped.hpp"
1918
#include "geometry_msgs/msg/pose_stamped.hpp"
2019
#include "visualization_msgs/msg/marker.hpp"
2120

2221
namespace nav2_graceful_controller
2322
{
24-
/**
25-
* @brief Create a PointStamped message of the motion target for
26-
* debugging / visualization porpuses.
27-
*
28-
* @param motion_target Motion target in PoseStamped format
29-
* @return geometry_msgs::msg::PointStamped Motion target in PointStamped format
30-
*/
31-
geometry_msgs::msg::PointStamped createMotionTargetMsg(
32-
const geometry_msgs::msg::PoseStamped & motion_target);
33-
3423
/**
3524
* @brief Create a flat circle marker of radius slowdown_radius around the motion target for
3625
* debugging / visualization porpuses.

nav2_graceful_controller/src/graceful_controller.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ void GracefulController::configure(
5858
// Publishers
5959
transformed_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>("transformed_global_plan", 1);
6060
local_plan_pub_ = node->create_publisher<nav_msgs::msg::Path>("local_plan", 1);
61-
motion_target_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>("motion_target", 1);
61+
motion_target_pub_ = node->create_publisher<geometry_msgs::msg::PoseStamped>("motion_target", 1);
6262
slowdown_pub_ = node->create_publisher<visualization_msgs::msg::Marker>("slowdown", 1);
6363

6464
RCLCPP_INFO(logger_, "Configured Graceful Motion Controller: %s", plugin_name_.c_str());
@@ -230,8 +230,7 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
230230
if (simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) {
231231
// Successfully simulated to target_pose - compute velocity at this moment
232232
// Publish the selected target_pose
233-
auto motion_target_point = nav2_graceful_controller::createMotionTargetMsg(target_pose);
234-
motion_target_pub_->publish(motion_target_point);
233+
motion_target_pub_->publish(target_pose);
235234
// Publish marker for slowdown radius around motion target for debugging / visualization
236235
auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker(
237236
target_pose, params_->slowdown_radius);

nav2_graceful_controller/src/utils.cpp

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -17,16 +17,6 @@
1717
namespace nav2_graceful_controller
1818
{
1919

20-
geometry_msgs::msg::PointStamped createMotionTargetMsg(
21-
const geometry_msgs::msg::PoseStamped & motion_target)
22-
{
23-
geometry_msgs::msg::PointStamped motion_target_point;
24-
motion_target_point.header = motion_target.header;
25-
motion_target_point.point = motion_target.pose.position;
26-
motion_target_point.point.z = 0.01;
27-
return motion_target_point;
28-
}
29-
3020
visualization_msgs::msg::Marker createSlowdownMarker(
3121
const geometry_msgs::msg::PoseStamped & motion_target, const double & slowdown_radius)
3222
{

nav2_graceful_controller/test/test_graceful_controller.cpp

Lines changed: 0 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -59,12 +59,6 @@ class GMControllerFixture : public nav2_graceful_controller::GracefulController
5959

6060
nav_msgs::msg::Path getPlan() {return path_handler_->getPlan();}
6161

62-
geometry_msgs::msg::PointStamped createMotionTargetMsg(
63-
const geometry_msgs::msg::PoseStamped & motion_target)
64-
{
65-
return nav2_graceful_controller::createMotionTargetMsg(motion_target);
66-
}
67-
6862
visualization_msgs::msg::Marker createSlowdownMarker(
6963
const geometry_msgs::msg::PoseStamped & motion_target)
7064
{
@@ -345,34 +339,6 @@ TEST(GracefulControllerTest, dynamicParameters) {
345339
EXPECT_EQ(controller->getAllowBackward(), false);
346340
}
347341

348-
TEST(GracefulControllerTest, createMotionTargetMsg) {
349-
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("testGraceful");
350-
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());
351-
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>("global_costmap");
352-
353-
// Create controller
354-
auto controller = std::make_shared<GMControllerFixture>();
355-
costmap_ros->on_configure(rclcpp_lifecycle::State());
356-
controller->configure(node, "test", tf, costmap_ros);
357-
controller->activate();
358-
359-
// Create motion target
360-
geometry_msgs::msg::PoseStamped motion_target;
361-
motion_target.header.frame_id = "map";
362-
motion_target.pose.position.x = 1.0;
363-
motion_target.pose.position.y = 2.0;
364-
motion_target.pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0));
365-
366-
// Create motion target message
367-
auto motion_target_msg = controller->createMotionTargetMsg(motion_target);
368-
369-
// Check results
370-
EXPECT_EQ(motion_target_msg.header.frame_id, "map");
371-
EXPECT_EQ(motion_target_msg.point.x, 1.0);
372-
EXPECT_EQ(motion_target_msg.point.y, 2.0);
373-
EXPECT_EQ(motion_target_msg.point.z, 0.01);
374-
}
375-
376342
TEST(GracefulControllerTest, createSlowdownMsg) {
377343
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("testGraceful");
378344
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());

0 commit comments

Comments
 (0)