Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(default_ad_api_helpers): support goal modification for rviz #3370

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 7 additions & 6 deletions system/default_ad_api_helpers/ad_api_adaptors/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,10 @@ When a goal pose topic is received, reset the waypoints and call the API.
When a waypoint pose topic is received, append it to the end of the waypoints to call the API.
The clear API is called automatically before setting the route.

| Interface | Local Name | Global Name | Description |
| ------------ | ---------------- | ------------------------------------- | --------------------------- |
| Subscription | ~/input/goal | /planning/mission_planning/goal | The goal pose of route. |
| Subscription | ~/input/waypoint | /planning/mission_planning/checkpoint | The waypoint pose of route. |
| Client | - | /api/routing/clear_route | The route clear API. |
| Client | - | /api/routing/set_route_points | The route points set API. |
| Interface | Local Name | Global Name | Description |
| ------------ | ------------------ | ------------------------------------- | -------------------------------------------------- |
| Subscription | ~/input/fixed_goal | /planning/mission_planning/goal | The goal pose of route. Disable goal modification. |
| Subscription | ~/input/rough_goal | /rviz/routing/rough_goal | The goal pose of route. Enable goal modification. |
| Subscription | ~/input/waypoint | /planning/mission_planning/checkpoint | The waypoint pose of route. |
| Client | - | /api/routing/clear_route | The route clear API. |
| Client | - | /api/routing/set_route_points | The route points set API. |
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@
<remap from="~/partial_map_load" to="/map/get_partial_pointcloud_map"/>
</node>
<node pkg="ad_api_adaptors" exec="routing_adaptor" name="routing_adaptor">
<remap from="~/input/goal" to="/planning/mission_planning/goal"/>
<remap from="~/input/fixed_goal" to="/planning/mission_planning/goal"/>
<remap from="~/input/rough_goal" to="/rviz/routing/rough_goal"/>
<remap from="~/input/waypoint" to="/planning/mission_planning/checkpoint"/>
</node>
</group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,14 @@ namespace ad_api_adaptors

RoutingAdaptor::RoutingAdaptor() : Node("routing_adaptor")
{
sub_goal_ = create_subscription<PoseStamped>(
"~/input/goal", 5, std::bind(&RoutingAdaptor::on_goal, this, std::placeholders::_1));
using std::placeholders::_1;

sub_fixed_goal_ = create_subscription<PoseStamped>(
"~/input/fixed_goal", 3, std::bind(&RoutingAdaptor::on_fixed_goal, this, _1));
sub_rough_goal_ = create_subscription<PoseStamped>(
"~/input/rough_goal", 3, std::bind(&RoutingAdaptor::on_rough_goal, this, _1));
sub_waypoint_ = create_subscription<PoseStamped>(
"~/input/waypoint", 5, std::bind(&RoutingAdaptor::on_waypoint, this, std::placeholders::_1));
"~/input/waypoint", 10, std::bind(&RoutingAdaptor::on_waypoint, this, _1));

const auto adaptor = component_interface_utils::NodeAdaptor(this);
adaptor.init_cli(cli_route_);
Expand Down Expand Up @@ -65,12 +69,22 @@ void RoutingAdaptor::on_timer()
}
}

void RoutingAdaptor::on_goal(const PoseStamped::ConstSharedPtr pose)
void RoutingAdaptor::on_fixed_goal(const PoseStamped::ConstSharedPtr pose)
{
request_timing_control_ = 1;
route_->header = pose->header;
route_->goal = pose->pose;
route_->waypoints.clear();
route_->option.allow_goal_modification = false;
}

void RoutingAdaptor::on_rough_goal(const PoseStamped::ConstSharedPtr pose)
{
request_timing_control_ = 1;
route_->header = pose->header;
route_->goal = pose->pose;
route_->waypoints.clear();
route_->option.allow_goal_modification = true;
}

void RoutingAdaptor::on_waypoint(const PoseStamped::ConstSharedPtr pose)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ class RoutingAdaptor : public rclcpp::Node
component_interface_utils::Client<SetRoutePoints>::SharedPtr cli_route_;
component_interface_utils::Client<ClearRoute>::SharedPtr cli_clear_;
component_interface_utils::Subscription<RouteState>::SharedPtr sub_state_;
rclcpp::Subscription<PoseStamped>::SharedPtr sub_goal_;
rclcpp::Subscription<PoseStamped>::SharedPtr sub_fixed_goal_;
rclcpp::Subscription<PoseStamped>::SharedPtr sub_rough_goal_;
rclcpp::Subscription<PoseStamped>::SharedPtr sub_waypoint_;
rclcpp::TimerBase::SharedPtr timer_;

Expand All @@ -49,7 +50,8 @@ class RoutingAdaptor : public rclcpp::Node
RouteState::Message::_state_type state_;

void on_timer();
void on_goal(const PoseStamped::ConstSharedPtr pose);
void on_fixed_goal(const PoseStamped::ConstSharedPtr pose);
void on_rough_goal(const PoseStamped::ConstSharedPtr pose);
void on_waypoint(const PoseStamped::ConstSharedPtr pose);
};

Expand Down