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(vehicle_cmd_gate): add multiple pause source ability #3435

Closed
Closed
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
33 changes: 24 additions & 9 deletions control/vehicle_cmd_gate/src/pause_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,24 +24,23 @@ PauseInterface::PauseInterface(rclcpp::Node * node) : node_(node)
adaptor.init_pub(pub_is_paused_);
adaptor.init_pub(pub_is_start_requested_);

is_paused_ = false;
pause_state_.data = false;
pause_state_.requested_sources.clear();
is_start_requested_ = false;
publish();
}

bool PauseInterface::is_paused()
{
return is_paused_;
return pause_state_.data;
}

void PauseInterface::publish()
{
if (prev_is_paused_ != is_paused_) {
IsPaused::Message msg;
msg.stamp = node_->now();
msg.data = is_paused_;
pub_is_paused_->publish(msg);
prev_is_paused_ = is_paused_;
if (prev_pause_map_ != pause_map_) {
update_pause_state();
pub_is_paused_->publish(pause_state_);
prev_pause_map_ = pause_map_;
}

if (prev_is_start_requested_ != is_start_requested_) {
Expand All @@ -61,8 +60,24 @@ void PauseInterface::update(const AckermannControlCommand & control)
void PauseInterface::on_pause(
const SetPause::Service::Request::SharedPtr req, const SetPause::Service::Response::SharedPtr res)
{
is_paused_ = req->pause;
pause_map_[req->request_source] = req->pause;
res->status.success = true;
}

void PauseInterface::update_pause_state()
{
pause_state_.stamp = node_->now();
pause_state_.requested_sources.clear();
pause_state_.data = false;

if (pause_map_.empty()) {
return;
}
for (auto & itr : pause_map_) {
if (itr.second) {
pause_state_.data = true;
pause_state_.requested_sources.push_back(itr.first);
}
}
}
} // namespace vehicle_cmd_gate
10 changes: 8 additions & 2 deletions control/vehicle_cmd_gate/src/pause_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>

#include <string>
#include <unordered_map>

namespace vehicle_cmd_gate
{

Expand All @@ -40,10 +43,11 @@ class PauseInterface
void update(const AckermannControlCommand & control);

private:
bool is_paused_;
bool is_start_requested_;
std::optional<bool> prev_is_paused_;
std::optional<bool> prev_is_start_requested_;
IsPaused::Message pause_state_;
std::unordered_map<std::string, bool> pause_map_;
std::optional<std::unordered_map<std::string, bool>> prev_pause_map_;

rclcpp::Node * node_;
component_interface_utils::Service<SetPause>::SharedPtr srv_set_pause_;
Expand All @@ -53,6 +57,8 @@ class PauseInterface
void on_pause(
const SetPause::Service::Request::SharedPtr req,
const SetPause::Service::Response::SharedPtr res);

void update_pause_state();
};

} // namespace vehicle_cmd_gate
Expand Down