Skip to content

Commit

Permalink
revert: engage button action in autoware_state_panel (#1079)
Browse files Browse the repository at this point in the history
* Revert "fix(autoware_state_panel): fix message type for /api/autoware/get/engage (#666)"

This reverts commit 49cc906.

* Revert "fix(tier4_state_rviz_plugin): change service and topic name for engage (#633)"

This reverts commit 15f43bc.
  • Loading branch information
h-ohta authored Jun 13, 2022
1 parent 865ba85 commit c2c7b16
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
8 changes: 4 additions & 4 deletions common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,11 +137,11 @@ void AutowareStatePanel::onInitialize()
sub_gear_ = raw_node_->create_subscription<autoware_auto_vehicle_msgs::msg::GearReport>(
"/vehicle/status/gear_status", 10, std::bind(&AutowareStatePanel::onShift, this, _1));

sub_engage_ = raw_node_->create_subscription<autoware_auto_vehicle_msgs::msg::Engage>(
"/api/autoware/get/engage", 10, std::bind(&AutowareStatePanel::onEngageStatus, this, _1));
sub_engage_ = raw_node_->create_subscription<tier4_external_api_msgs::msg::EngageStatus>(
"/api/external/get/engage", 10, std::bind(&AutowareStatePanel::onEngageStatus, this, _1));

client_engage_ = raw_node_->create_client<tier4_external_api_msgs::srv::Engage>(
"/api/autoware/set/engage", rmw_qos_profile_services_default);
"/api/external/set/engage", rmw_qos_profile_services_default);

pub_velocity_limit_ = raw_node_->create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
"/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1));
Expand Down Expand Up @@ -248,7 +248,7 @@ void AutowareStatePanel::onShift(
}

void AutowareStatePanel::onEngageStatus(
const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg)
const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg)
{
current_engage_ = msg->engage;
engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_)));
Expand Down
6 changes: 3 additions & 3 deletions common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,10 @@
#include <rviz_common/panel.hpp>

#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
#include <tier4_control_msgs/msg/external_command_selector_mode.hpp>
#include <tier4_control_msgs/msg/gate_mode.hpp>
#include <tier4_external_api_msgs/msg/engage_status.hpp>
#include <tier4_external_api_msgs/srv/engage.hpp>
#include <tier4_planning_msgs/msg/approval.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
Expand All @@ -54,7 +54,7 @@ public Q_SLOTS:
const tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr msg);
void onAutowareState(const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg);
void onShift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg);
void onEngageStatus(const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg);
void onEngageStatus(const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg);

rclcpp::Node::SharedPtr raw_node_;
rclcpp::Subscription<tier4_control_msgs::msg::GateMode>::SharedPtr sub_gate_mode_;
Expand All @@ -63,7 +63,7 @@ public Q_SLOTS:
rclcpp::Subscription<autoware_auto_system_msgs::msg::AutowareState>::SharedPtr
sub_autoware_state_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::GearReport>::SharedPtr sub_gear_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::Engage>::SharedPtr sub_engage_;
rclcpp::Subscription<tier4_external_api_msgs::msg::EngageStatus>::SharedPtr sub_engage_;

rclcpp::Client<tier4_external_api_msgs::srv::Engage>::SharedPtr client_engage_;

Expand Down

0 comments on commit c2c7b16

Please sign in to comment.