Skip to content

Commit e8f952a

Browse files
committed
Revert "Use PoseStampedArray (ros-navigation#4791)"
This reverts commit 02336a2.
1 parent ac98371 commit e8f952a

33 files changed

+175
-280
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp

Lines changed: 3 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,8 @@
2323
#include "rclcpp/node.hpp"
2424
#include "behaviortree_cpp/behavior_tree.h"
2525
#include "geometry_msgs/msg/point.hpp"
26-
#include "geometry_msgs/msg/pose_stamped.hpp"
27-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
2826
#include "geometry_msgs/msg/quaternion.hpp"
27+
#include "geometry_msgs/msg/pose_stamped.hpp"
2928
#include "nav_msgs/msg/path.hpp"
3029

3130
namespace BT
@@ -113,6 +112,7 @@ inline geometry_msgs::msg::PoseStamped convertFromString(const StringView key)
113112
template<>
114113
inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const StringView key)
115114
{
115+
// 9 real numbers separated by semicolons
116116
auto parts = BT::splitString(key, ';');
117117
if (parts.size() % 9 != 0) {
118118
throw std::runtime_error("invalid number of fields for std::vector<PoseStamped> attribute)");
@@ -135,38 +135,6 @@ inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const Stri
135135
}
136136
}
137137

138-
/**
139-
* @brief Parse XML string to geometry_msgs::msg::PoseStampedArray
140-
* @param key XML string
141-
* @return geometry_msgs::msg::PoseStampedArray
142-
*/
143-
template<>
144-
inline geometry_msgs::msg::PoseStampedArray convertFromString(const StringView key)
145-
{
146-
auto parts = BT::splitString(key, ';');
147-
if ((parts.size() - 2) % 9 != 0) {
148-
throw std::runtime_error("invalid number of fields for PoseStampedArray attribute)");
149-
} else {
150-
geometry_msgs::msg::PoseStampedArray pose_stamped_array;
151-
pose_stamped_array.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
152-
pose_stamped_array.header.frame_id = BT::convertFromString<std::string>(parts[1]);
153-
for (size_t i = 2; i < parts.size(); i += 9) {
154-
geometry_msgs::msg::PoseStamped pose_stamped;
155-
pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
156-
pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
157-
pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
158-
pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
159-
pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
160-
pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
161-
pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
162-
pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
163-
pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
164-
pose_stamped_array.poses.push_back(pose_stamped);
165-
}
166-
return pose_stamped_array;
167-
}
168-
}
169-
170138
/**
171139
* @brief Parse XML string to nav_msgs::msg::Path
172140
* @param key XML string
@@ -175,6 +143,7 @@ inline geometry_msgs::msg::PoseStampedArray convertFromString(const StringView k
175143
template<>
176144
inline nav_msgs::msg::Path convertFromString(const StringView key)
177145
{
146+
// 9 real numbers separated by semicolons
178147
auto parts = BT::splitString(key, ';');
179148
if ((parts.size() - 2) % 9 != 0) {
180149
throw std::runtime_error("invalid number of fields for Path attribute)");

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ class ComputePathThroughPosesAction
7575
{
7676
return providedBasicPorts(
7777
{
78-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
78+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
7979
"goals",
8080
"Destinations to plan through"),
8181
BT::InputPort<geometry_msgs::msg::PoseStamped>(

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,8 @@
1818
#include <string>
1919
#include <vector>
2020

21-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
21+
#include "geometry_msgs/msg/point.hpp"
22+
#include "geometry_msgs/msg/quaternion.hpp"
2223
#include "nav2_msgs/action/navigate_through_poses.hpp"
2324
#include "nav2_behavior_tree/bt_action_node.hpp"
2425

@@ -73,7 +74,7 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
7374
{
7475
return providedBasicPorts(
7576
{
76-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
77+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
7778
"goals", "Destinations to plan through"),
7879
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
7980
BT::OutputPort<ActionResult::_error_code_type>(

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
#include <string>
2121

2222
#include "rclcpp/rclcpp.hpp"
23-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
23+
#include "geometry_msgs/msg/pose_stamped.hpp"
2424
#include "nav2_behavior_tree/bt_service_node.hpp"
2525
#include "nav2_msgs/srv/get_costs.hpp"
2626

@@ -30,6 +30,8 @@ namespace nav2_behavior_tree
3030
class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
3131
{
3232
public:
33+
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
34+
3335
/**
3436
* @brief A constructor for nav2_behavior_tree::RemoveInCollisionGoals
3537
* @param service_node_name Service name this node creates a client for
@@ -52,25 +54,23 @@ class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
5254
{
5355
return providedBasicPorts(
5456
{
55-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals",
56-
"Original goals to remove from"),
57+
BT::InputPort<Goals>("input_goals", "Original goals to remove from"),
5758
BT::InputPort<double>(
5859
"cost_threshold", 254.0,
5960
"Cost threshold for considering a goal in collision"),
6061
BT::InputPort<bool>("use_footprint", true, "Whether to use footprint cost"),
6162
BT::InputPort<bool>(
6263
"consider_unknown_as_obstacle", false,
6364
"Whether to consider unknown cost as obstacle"),
64-
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals",
65-
"Goals with in-collision goals removed"),
65+
BT::OutputPort<Goals>("output_goals", "Goals with in-collision goals removed"),
6666
});
6767
}
6868

6969
private:
7070
bool use_footprint_;
7171
bool consider_unknown_as_obstacle_;
7272
double cost_threshold_;
73-
geometry_msgs::msg::PoseStampedArray input_goals_;
73+
Goals input_goals_;
7474
};
7575

7676
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
#include <memory>
2020
#include <string>
2121

22-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
22+
#include "geometry_msgs/msg/pose_stamped.hpp"
2323
#include "nav2_util/geometry_utils.hpp"
2424
#include "nav2_util/robot_utils.hpp"
2525
#include "behaviortree_cpp/action_node.h"
@@ -31,6 +31,8 @@ namespace nav2_behavior_tree
3131
class RemovePassedGoals : public BT::ActionNodeBase
3232
{
3333
public:
34+
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
35+
3436
RemovePassedGoals(
3537
const std::string & xml_tag_name,
3638
const BT::NodeConfiguration & conf);
@@ -43,10 +45,8 @@ class RemovePassedGoals : public BT::ActionNodeBase
4345
static BT::PortsList providedPorts()
4446
{
4547
return {
46-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals",
47-
"Original goals to remove viapoints from"),
48-
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals",
49-
"Goals with passed viapoints removed"),
48+
BT::InputPort<Goals>("input_goals", "Original goals to remove viapoints from"),
49+
BT::OutputPort<Goals>("output_goals", "Goals with passed viapoints removed"),
5050
BT::InputPort<double>("radius", 0.5, "radius to goal for it to be considered for removal"),
5151
BT::InputPort<std::string>("global_frame", "Global frame"),
5252
BT::InputPort<std::string>("robot_base_frame", "Robot base frame"),

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#include "rclcpp/rclcpp.hpp"
2222

2323
#include "behaviortree_cpp/condition_node.h"
24-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
24+
#include "geometry_msgs/msg/pose_stamped.hpp"
2525
#include "nav2_behavior_tree/bt_utils.hpp"
2626

2727

@@ -59,7 +59,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
5959
static BT::PortsList providedPorts()
6060
{
6161
return {
62-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
62+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
6363
"goals", "Vector of navigation goals"),
6464
BT::InputPort<geometry_msgs::msg::PoseStamped>(
6565
"goal", "Navigation goal"),
@@ -70,7 +70,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
7070
bool first_time;
7171
rclcpp::Node::SharedPtr node_;
7272
geometry_msgs::msg::PoseStamped goal_;
73-
geometry_msgs::msg::PoseStampedArray goals_;
73+
std::vector<geometry_msgs::msg::PoseStamped> goals_;
7474
};
7575

7676
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
#include <vector>
2020

2121
#include "behaviortree_cpp/condition_node.h"
22-
#include "geometry_msgs/msg/pose_stamped_array.hpp"
22+
#include "geometry_msgs/msg/pose_stamped.hpp"
2323
#include "nav2_behavior_tree/bt_utils.hpp"
2424

2525
namespace nav2_behavior_tree
@@ -56,7 +56,7 @@ class GoalUpdatedCondition : public BT::ConditionNode
5656
static BT::PortsList providedPorts()
5757
{
5858
return {
59-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
59+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
6060
"goals", "Vector of navigation goals"),
6161
BT::InputPort<geometry_msgs::msg::PoseStamped>(
6262
"goal", "Navigation goal"),
@@ -65,7 +65,7 @@ class GoalUpdatedCondition : public BT::ConditionNode
6565

6666
private:
6767
geometry_msgs::msg::PoseStamped goal_;
68-
geometry_msgs::msg::PoseStampedArray goals_;
68+
std::vector<geometry_msgs::msg::PoseStamped> goals_;
6969
};
7070

7171
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ class GoalUpdatedController : public BT::DecoratorNode
5050
static BT::PortsList providedPorts()
5151
{
5252
return {
53-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
53+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
5454
"goals", "Vector of navigation goals"),
5555
BT::InputPort<geometry_msgs::msg::PoseStamped>(
5656
"goal", "Navigation goal"),
@@ -66,7 +66,7 @@ class GoalUpdatedController : public BT::DecoratorNode
6666

6767
bool goal_was_updated_;
6868
geometry_msgs::msg::PoseStamped goal_;
69-
geometry_msgs::msg::PoseStampedArray goals_;
69+
std::vector<geometry_msgs::msg::PoseStamped> goals_;
7070
};
7171

7272
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class SpeedController : public BT::DecoratorNode
5858
BT::InputPort<double>("max_rate", 1.0, "Maximum rate"),
5959
BT::InputPort<double>("min_speed", 0.0, "Minimum speed"),
6060
BT::InputPort<double>("max_speed", 0.5, "Maximum speed"),
61-
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
61+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
6262
"goals", "Vector of navigation goals"),
6363
BT::InputPort<geometry_msgs::msg::PoseStamped>(
6464
"goal", "Navigation goal"),
@@ -120,7 +120,7 @@ class SpeedController : public BT::DecoratorNode
120120

121121
// current goal
122122
geometry_msgs::msg::PoseStamped goal_;
123-
geometry_msgs::msg::PoseStampedArray goals_;
123+
std::vector<geometry_msgs::msg::PoseStamped> goals_;
124124
};
125125

126126
} // namespace nav2_behavior_tree

nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -39,15 +39,15 @@ void RemoveInCollisionGoals::on_tick()
3939
getInput("input_goals", input_goals_);
4040
getInput("consider_unknown_as_obstacle", consider_unknown_as_obstacle_);
4141

42-
if (input_goals_.poses.empty()) {
42+
if (input_goals_.empty()) {
4343
setOutput("output_goals", input_goals_);
4444
should_send_request_ = false;
4545
return;
4646
}
4747
request_ = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
4848
request_->use_footprint = use_footprint_;
4949

50-
for (const auto & goal : input_goals_.poses) {
50+
for (const auto & goal : input_goals_) {
5151
request_->poses.push_back(goal);
5252
}
5353
}
@@ -63,16 +63,16 @@ BT::NodeStatus RemoveInCollisionGoals::on_completion(
6363
return BT::NodeStatus::FAILURE;
6464
}
6565

66-
geometry_msgs::msg::PoseStampedArray valid_goal_poses;
66+
Goals valid_goal_poses;
6767
for (size_t i = 0; i < response->costs.size(); ++i) {
6868
if ((response->costs[i] == 255 && !consider_unknown_as_obstacle_) ||
6969
response->costs[i] < cost_threshold_)
7070
{
71-
valid_goal_poses.poses.push_back(input_goals_.poses[i]);
71+
valid_goal_poses.push_back(input_goals_[i]);
7272
}
7373
}
7474
// Inform if all goals have been removed
75-
if (valid_goal_poses.poses.empty()) {
75+
if (valid_goal_poses.empty()) {
7676
RCLCPP_INFO(
7777
node_->get_logger(),
7878
"All goals are in collision and have been removed from the list");

0 commit comments

Comments
 (0)