Skip to content

Commit

Permalink
add description
Browse files Browse the repository at this point in the history
  • Loading branch information
facontidavide committed Jan 26, 2024
1 parent c6f3a29 commit 8bb0c7c
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,10 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>("goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,10 @@ class GoalUpdatedCondition : public BT::ConditionNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>("goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,10 @@ class GoalUpdatedController : public BT::DecoratorNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>("goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,10 @@ class SpeedController : public BT::DecoratorNode
BT::InputPort<double>("max_rate", 1.0, "Maximum rate"),
BT::InputPort<double>("min_speed", 0.0, "Minimum speed"),
BT::InputPort<double>("max_speed", 0.5, "Maximum speed"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>("goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
};
}

Expand Down

0 comments on commit 8bb0c7c

Please sign in to comment.