Skip to content

Commit

Permalink
fix: merge operation mode state message
Browse files Browse the repository at this point in the history
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
  • Loading branch information
isamu-takagi committed Aug 10, 2022
1 parent ff081d9 commit 2076df8
Show file tree
Hide file tree
Showing 7 changed files with 32 additions and 47 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,7 @@

#include <rclcpp/qos.hpp>

#include <tier4_system_msgs/msg/operation_mode_available.hpp>
#include <tier4_system_msgs/msg/operation_mode_state.hpp>
#include <autoware_ad_api_msgs/msg/operation_mode_state.hpp>
#include <tier4_system_msgs/srv/change_autoware_control.hpp>
#include <tier4_system_msgs/srv/change_operation_mode.hpp>

Expand All @@ -39,22 +38,13 @@ struct ChangeOperationMode

struct OperationModeState
{
using Message = tier4_system_msgs::msg::OperationModeState;
using Message = autoware_ad_api_msgs::msg::OperationModeState;
static constexpr char name[] = "/system/operation_mode/state";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct AutonomousModeAvailable
{
using Message = tier4_system_msgs::msg::OperationModeAvailable;
static constexpr char name[] = "/system/operation_mode/autonomous_available";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace system_interface

#endif // COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_
14 changes: 7 additions & 7 deletions control/operation_mode_transition_manager/src/data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,23 +52,23 @@ std::optional<OperationMode> toEnum(const ChangeOperationMode::Request & request
return std::nullopt;
}

OperationModeStateValue toMsg(const OperationMode mode)
OperationModeValue toMsg(const OperationMode mode)
{
const auto get_operation_mode = [](const OperationMode mode) {
switch (mode) {
case OperationMode::STOP:
return OperationModeStateValue::STOP;
return OperationModeValue::STOP;
case OperationMode::AUTONOMOUS:
return OperationModeStateValue::AUTONOMOUS;
return OperationModeValue::AUTONOMOUS;
case OperationMode::LOCAL:
return OperationModeStateValue::LOCAL;
return OperationModeValue::LOCAL;
case OperationMode::REMOTE:
return OperationModeStateValue::REMOTE;
return OperationModeValue::REMOTE;
}
return OperationModeStateValue::UNKNOWN;
return OperationModeValue::UNKNOWN;
};

OperationModeStateValue operation;
OperationModeValue operation;
operation.mode = get_operation_mode(mode);
return operation;
}
Expand Down
8 changes: 4 additions & 4 deletions control/operation_mode_transition_manager/src/data.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_ad_api_msgs/msg/operation_mode_state.hpp>
#include <autoware_ad_api_msgs/srv/change_operation_mode.hpp>
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <tier4_system_msgs/msg/operation_mode_state.hpp>
#include <tier4_system_msgs/srv/change_operation_mode.hpp>
#include <tier4_vehicle_msgs/srv/control_mode_request.hpp>

Expand All @@ -31,8 +31,8 @@ namespace operation_mode_transition_manager
{

using ServiceResponse = autoware_ad_api_msgs::srv::ChangeOperationMode::Response;
using OperationModeState = tier4_system_msgs::msg::OperationModeState;
using OperationModeStateValue = OperationModeState::_operation_type;
using OperationModeState = autoware_ad_api_msgs::msg::OperationModeState;
using OperationModeValue = OperationModeState::_operation_type;
using ChangeOperationMode = tier4_system_msgs::srv::ChangeOperationMode;
using ControlModeRequest = tier4_vehicle_msgs::srv::ControlModeRequest;
using ControlModeReport = autoware_auto_vehicle_msgs::msg::ControlModeReport;
Expand Down Expand Up @@ -79,7 +79,7 @@ struct StableCheckParam

std::string toString(const std::optional<OperationMode> mode);
std::optional<OperationMode> toEnum(const ChangeOperationMode::Request & request);
OperationModeStateValue toMsg(const OperationMode mode);
OperationModeValue toMsg(const OperationMode mode);

} // namespace operation_mode_transition_manager

Expand Down
32 changes: 15 additions & 17 deletions control/operation_mode_transition_manager/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ OperationModeTransitionManager::OperationModeTransitionManager(const rclcpp::Nod
srv_autoware_control, this, &OperationModeTransitionManager::onChangeAutowareControl);
node.init_srv(srv_operation_mode, this, &OperationModeTransitionManager::onChangeOperationMode);
node.init_pub(pub_operation_mode_);
node.init_pub(pub_auto_mode_available_);
}

// timer
Expand All @@ -54,7 +53,7 @@ OperationModeTransitionManager::OperationModeTransitionManager(const rclcpp::Nod
transition_timeout_ = declare_parameter<double>("transition_timeout");
current_mode_ = OperationMode::STOP;
transition_ = nullptr;
gate_operation_mode_.operation.mode = OperationModeStateValue::UNKNOWN;
gate_operation_mode_.operation.mode = OperationModeValue::UNKNOWN;
gate_operation_mode_.is_in_transition = false;
control_mode_report_.mode = ControlModeReport::NO_COMMAND;

Expand Down Expand Up @@ -206,23 +205,22 @@ void OperationModeTransitionManager::onTimer()

void OperationModeTransitionManager::publishData()
{
const bool current_control = control_mode_report_.mode == ControlModeReport::AUTONOMOUS;
const auto time = now();

OperationModeStateAPI::Message operation_mode_state;
operation_mode_state.operation = toMsg(current_mode_);
operation_mode_state.is_in_transition = transition_ ? true : false;
if (prev_pub_state_ != operation_mode_state) {
prev_pub_state_ = operation_mode_state;
operation_mode_state.stamp = time;
pub_operation_mode_->publish(operation_mode_state);
}

AutoModeAvailableAPI::Message available;
available.available = modes_.at(OperationMode::AUTONOMOUS)->isModeChangeAvailable();
if (prev_pub_available_ != available) {
prev_pub_available_ = available;
available.stamp = time;
pub_auto_mode_available_->publish(available);
OperationModeStateAPI::Message state;
state.operation = toMsg(current_mode_);
state.is_autoware_control_enabled = current_control;
state.is_in_transition = transition_ ? true : false;
state.change_to_stop = modes_.at(OperationMode::STOP)->isModeChangeAvailable();
state.change_to_autonomous = modes_.at(OperationMode::AUTONOMOUS)->isModeChangeAvailable();
state.change_to_local = modes_.at(OperationMode::LOCAL)->isModeChangeAvailable();
state.change_to_remote = modes_.at(OperationMode::REMOTE)->isModeChangeAvailable();

if (prev_state_ != state) {
prev_state_ = state;
state.stamp = time;
pub_operation_mode_->publish(state);
}

ModeChangeBase::DebugInfo debug_info = modes_.at(OperationMode::AUTONOMOUS)->getDebugInfo();
Expand Down
5 changes: 1 addition & 4 deletions control/operation_mode_transition_manager/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,9 @@ class OperationModeTransitionManager : public rclcpp::Node
using ChangeAutowareControlAPI = system_interface::ChangeAutowareControl;
using ChangeOperationModeAPI = system_interface::ChangeOperationMode;
using OperationModeStateAPI = system_interface::OperationModeState;
using AutoModeAvailableAPI = system_interface::AutonomousModeAvailable;
component_interface_utils::Service<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control;
component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode;
component_interface_utils::Publisher<OperationModeStateAPI>::SharedPtr pub_operation_mode_;
component_interface_utils::Publisher<AutoModeAvailableAPI>::SharedPtr pub_auto_mode_available_;
void onChangeAutowareControl(
const ChangeAutowareControlAPI::Service::Request::SharedPtr request,
const ChangeAutowareControlAPI::Service::Response::SharedPtr response);
Expand Down Expand Up @@ -70,8 +68,7 @@ class OperationModeTransitionManager : public rclcpp::Node
OperationModeState gate_operation_mode_;
ControlModeReport control_mode_report_;

std::optional<OperationModeStateAPI::Message> prev_pub_state_;
std::optional<AutoModeAvailableAPI::Message> prev_pub_available_;
std::optional<OperationModeStateAPI::Message> prev_state_;
};

} // namespace operation_mode_transition_manager
Expand Down
2 changes: 1 addition & 1 deletion control/vehicle_cmd_gate/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
| `~/input/emergency/hazard_lights_cmd` | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command from emergency handler |
| `~/input/emergency/gear_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | gear command from emergency handler |
| `~/input/engage` | `autoware_auto_vehicle_msgs::msg::Engage` | engage signal |
| `~/input/operation_mode` | `tier4_system_msgs::msg::OperationModeState` | operation mode of Autoware |
| `~/input/operation_mode` | `autoware_ad_api_msgs::msg::OperationModeState` | operation mode of Autoware |

### Output

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <std_srvs/srv/trigger.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_ad_api_msgs/msg/operation_mode_state.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_system_msgs/msg/emergency_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
Expand All @@ -36,14 +37,14 @@
#include <tier4_external_api_msgs/msg/heartbeat.hpp>
#include <tier4_external_api_msgs/srv/engage.hpp>
#include <tier4_external_api_msgs/srv/set_emergency.hpp>
#include <tier4_system_msgs/msg/operation_mode_state.hpp>
#include <tier4_vehicle_msgs/msg/vehicle_emergency_stamped.hpp>

#include <memory>

namespace vehicle_cmd_gate
{

using autoware_ad_api_msgs::msg::OperationModeState;
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_system_msgs::msg::EmergencyState;
using autoware_auto_vehicle_msgs::msg::GearCommand;
Expand All @@ -54,7 +55,6 @@ using tier4_control_msgs::msg::GateMode;
using tier4_external_api_msgs::msg::Emergency;
using tier4_external_api_msgs::msg::Heartbeat;
using tier4_external_api_msgs::srv::SetEmergency;
using tier4_system_msgs::msg::OperationModeState;
using tier4_vehicle_msgs::msg::VehicleEmergencyStamped;

using diagnostic_msgs::msg::DiagnosticStatus;
Expand Down

0 comments on commit 2076df8

Please sign in to comment.