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(mrm_handler): input gear command (#8080) #1498

Merged
merged 1 commit into from
Aug 30, 2024
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
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ class MrmHandler : public rclcpp::Node
autoware::universe_utils::InterProcessPollingSubscriber<
autoware_adapi_v1_msgs::msg::OperationModeState>
sub_operation_mode_state_{this, "~/input/api/operation_mode/state"};
autoware::universe_utils::InterProcessPollingSubscriber<autoware_vehicle_msgs::msg::GearCommand>
sub_gear_cmd_{this, "~/input/gear"};

tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr operation_mode_availability_;

Expand Down Expand Up @@ -146,7 +148,6 @@ class MrmHandler : public rclcpp::Node
void handleFailedRequest();
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
bool isStopped();
bool isDrivingBackwards();
bool isEmergency() const;
bool isControlModeAutonomous();
bool isOperationModeAutonomous();
Expand Down
2 changes: 2 additions & 0 deletions system/mrm_handler/launch/mrm_handler.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<arg name="input_mrm_comfortable_stop_state" default="/system/mrm/comfortable_stop/status"/>
<arg name="input_mrm_emergency_stop_state" default="/system/mrm/emergency_stop/status"/>
<arg name="input_api_operation_mode_state" default="/api/operation_mode/state"/>
<arg name="input_gear" default="/control/command/gear_cmd"/>

<arg name="output_gear" default="/system/emergency/gear_cmd"/>
<arg name="output_hazard" default="/system/emergency/hazard_lights_cmd"/>
Expand All @@ -26,6 +27,7 @@
<remap from="~/input/mrm/comfortable_stop/status" to="$(var input_mrm_comfortable_stop_state)"/>
<remap from="~/input/mrm/emergency_stop/status" to="$(var input_mrm_emergency_stop_state)"/>
<remap from="~/input/api/operation_mode/state" to="$(var input_api_operation_mode_state)"/>
<remap from="~/input/gear" to="$(var input_gear)"/>

<remap from="~/output/gear" to="$(var output_gear)"/>
<remap from="~/output/hazard" to="$(var output_hazard)"/>
Expand Down
31 changes: 12 additions & 19 deletions system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,19 +130,20 @@ void MrmHandler::publishGearCmd()
{
using autoware_vehicle_msgs::msg::GearCommand;
GearCommand msg;

msg.stamp = this->now();
const auto command = [&]() {
// If stopped and use_parking is not true, send the last gear command
if (isStopped())
return (param_.use_parking_after_stopped) ? GearCommand::PARK : last_gear_command_;
return (isDrivingBackwards()) ? GearCommand::REVERSE : GearCommand::DRIVE;
}();

msg.command = command;
last_gear_command_ = msg.command;

if (isEmergency()) {
// gear command is created within mrm_handler
msg.command =
(param_.use_parking_after_stopped && isStopped()) ? GearCommand::PARK : last_gear_command_;
} else {
// use the same gear as the input gear
auto gear = sub_gear_cmd_.takeData();
msg.command = (gear == nullptr) ? last_gear_command_ : gear->command;
last_gear_command_ = msg.command;
}

pub_gear_cmd_->publish(msg);
return;
}

void MrmHandler::publishMrmState()
Expand Down Expand Up @@ -524,14 +525,6 @@ bool MrmHandler::isStopped()
return (std::abs(odom->twist.twist.linear.x) < th_stopped_velocity);
}

bool MrmHandler::isDrivingBackwards()
{
auto odom = sub_odom_.takeData();
if (odom == nullptr) return false;
constexpr auto th_moving_backwards = -0.001;
return odom->twist.twist.linear.x < th_moving_backwards;
}

bool MrmHandler::isEmergency() const
{
return !operation_mode_availability_->autonomous || is_emergency_holding_ ||
Expand Down
Loading