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

fix(rtc_interface): fix initial auto mode (#3029) #331

Merged
merged 2 commits into from
Mar 22, 2023
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 @@ -81,7 +81,7 @@ class RTCInterface
Module module_;
CooperateStatusArray registered_status_;
std::vector<CooperateCommand> stored_commands_;
bool is_auto_mode_;
bool is_auto_mode_init_;
bool is_locked_;

std::string cooperate_status_namespace_ = "/planning/cooperate_status";
Expand Down
8 changes: 3 additions & 5 deletions planning/rtc_interface/src/rtc_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace rtc_interface
{
RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name)
: logger_{node->get_logger().get_child("RTCInterface[" + name + "]")},
is_auto_mode_{false},
is_auto_mode_init_{false},
is_locked_{false}
{
using std::placeholders::_1;
Expand Down Expand Up @@ -156,7 +156,6 @@ void RTCInterface::updateCooperateCommandStatus(const std::vector<CooperateComma
if (itr != registered_status_.statuses.end()) {
itr->command_status = command.command;
itr->auto_mode = false;
is_auto_mode_ = false;
}
}
}
Expand All @@ -165,7 +164,7 @@ void RTCInterface::onAutoModeService(
const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response)
{
std::lock_guard<std::mutex> lock(mutex_);
is_auto_mode_ = request->enable;
is_auto_mode_init_ = request->enable;
for (auto & status : registered_status_.statuses) {
status.auto_mode = request->enable;
}
Expand All @@ -192,7 +191,7 @@ void RTCInterface::updateCooperateStatus(
status.command_status.type = Command::DEACTIVATE;
status.start_distance = start_distance;
status.finish_distance = finish_distance;
status.auto_mode = is_auto_mode_;
status.auto_mode = is_auto_mode_init_;
registered_status_.statuses.push_back(status);
return;
}
Expand All @@ -202,7 +201,6 @@ void RTCInterface::updateCooperateStatus(
itr->safe = safe;
itr->start_distance = start_distance;
itr->finish_distance = finish_distance;
itr->auto_mode = is_auto_mode_;
}

void RTCInterface::removeCooperateStatus(const UUID & uuid)
Expand Down