Skip to content

Commit

Permalink
fix(leader_election_converter): use adapi mrm state (#1472)
Browse files Browse the repository at this point in the history
fix: use adapi mrm state

Signed-off-by: TetsuKawa <[email protected]>
  • Loading branch information
TetsuKawa authored Aug 17, 2024
1 parent 07144ae commit 12da511
Show file tree
Hide file tree
Showing 6 changed files with 27 additions and 26 deletions.
15 changes: 9 additions & 6 deletions planning/trajectory_repeater/src/trajectory_repeater.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,26 +24,29 @@ TrajectoryRepeater::TrajectoryRepeater(const rclcpp::NodeOptions & node_options)

// Subscriber
sub_trajectory_ = create_subscription<autoware_auto_planning_msgs::msg::Trajectory>(
"~/input/trajectory", 10, std::bind(&TrajectoryRepeater::onTrajectory, this, std::placeholders::_1));
"~/input/trajectory", 10,
std::bind(&TrajectoryRepeater::onTrajectory, this, std::placeholders::_1));

// Publisher
pub_trajectory_ = create_publisher<autoware_auto_planning_msgs::msg::Trajectory>("~/output/trajectory", 10);
pub_trajectory_ =
create_publisher<autoware_auto_planning_msgs::msg::Trajectory>("~/output/trajectory", 10);

// Service

// Client

// Timer
using namespace std::literals::chrono_literals;
timer_ = rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&TrajectoryRepeater::onTimer, this));
timer_ =
rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&TrajectoryRepeater::onTimer, this));

// State

// Diagnostics

}

void TrajectoryRepeater::onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg)
void TrajectoryRepeater::onTrajectory(
const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg)
{
last_trajectory_ = msg;
}
Expand All @@ -54,7 +57,7 @@ void TrajectoryRepeater::onTimer()
RCLCPP_DEBUG(get_logger(), "No trajectory received");
return;
}

pub_trajectory_->publish(*last_trajectory_);
}

Expand Down
9 changes: 4 additions & 5 deletions planning/trajectory_repeater/src/trajectory_repeater.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TRAJECTORY_REPEATER__TRAJECTORY_REPEATER_HPP_
#define TRAJECTORY_REPEATER__TRAJECTORY_REPEATER_HPP_
#ifndef TRAJECTORY_REPEATER_HPP_
#define TRAJECTORY_REPEATER_HPP_

// include
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -46,15 +46,14 @@ class TrajectoryRepeater : public rclcpp::Node

// Timer
rclcpp::TimerBase::SharedPtr timer_;

void onTimer();

// State
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr last_trajectory_;

// Diagnostics

};
} // namespace trajectory_repeater

#endif // TRAJECTORY_REPEATER__TRAJECTORY_REPEATER_HPP_
#endif // TRAJECTORY_REPEATER_HPP_
12 changes: 6 additions & 6 deletions system/leader_election_converter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ In addition, it receives a udp packet`MrmState` and publish `/system/mrm_request

### Interface

| Interface Type | Interface Name | Data Type | Description |
| -------------- | ------------------------------ | ----------------------------------- | ------------------------ |
| subscriber | `/system/fail_safe/mrm_state` | `tier4_system_msgs/msg/MrmState` | MRM status of each ECU. |
| udp sender | none | `struct MrmState` | Same as above. |
| publisher | `/system/election/mrm_request` | `tier4_system_msgs/msg/MrmBehavior` | Request of MRM behavior. |
| udp receiver | none | `struct MrmRequest` | Same as above. |
| Interface Type | Interface Name | Data Type | Description |
| -------------- | ------------------------------ | ------------------------------------- | ------------------------ |
| subscriber | `/system/fail_safe/mrm_state` | `autoware_adapi_v1_msgs/msg/MrmState` | MRM status of each ECU. |
| udp sender | none | `struct MrmState` | Same as above. |
| publisher | `/system/election/mrm_request` | `tier4_system_msgs/msg/MrmBehavior` | Request of MRM behavior. |
| udp receiver | none | `struct MrmRequest` | Same as above. |

## log converter

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <tier4_system_msgs/msg/election_communication.hpp>
#include <tier4_system_msgs/msg/election_status.hpp>
#include <tier4_system_msgs/msg/mrm_state.hpp>

#include <atomic>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void MrmConverter::setSubscriber()
rclcpp::SubscriptionOptions options;
options.callback_group = callback_group_;

sub_mrm_state_ = node_->create_subscription<tier4_system_msgs::msg::MrmState>(
sub_mrm_state_ = node_->create_subscription<autoware_adapi_v1_msgs::msg::MrmState>(
"~/input/mrm_state", qos, std::bind(&MrmConverter::convertToUdp, this, std::placeholders::_1),
options);
}
Expand All @@ -77,11 +77,11 @@ void MrmConverter::setPublisher()
}

void MrmConverter::convertToUdp(
const tier4_system_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg)
const autoware_adapi_v1_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg)
{
MrmState mrm_state;
mrm_state.state = mrm_state_msg->state;
mrm_state.behavior = mrm_state_msg->behavior.type;
mrm_state.behavior = mrm_state_msg->behavior;

udp_mrm_state_sender_->send(mrm_state);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
#include <tier4_system_msgs/msg/mrm_state.hpp>

#include <atomic>
#include <memory>
Expand All @@ -33,8 +33,8 @@ namespace leader_election_converter

typedef struct MrmState
{
tier4_system_msgs::msg::MrmState::_state_type state;
tier4_system_msgs::msg::MrmBehavior::_type_type behavior;
autoware_adapi_v1_msgs::msg::MrmState::_state_type state;
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type behavior;
} MrmState;

typedef struct MrmRequest
Expand All @@ -55,14 +55,14 @@ class MrmConverter

private:
void startUdpReceiver(const std::string & src_ip, const std::string & src_port);
void convertToUdp(const tier4_system_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg);
void convertToUdp(const autoware_adapi_v1_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg);
void convertToTopic(const MrmRequest & mrm_request);

rclcpp::Node * node_;
std::unique_ptr<UdpSender<MrmState>> udp_mrm_state_sender_;
std::unique_ptr<UdpReceiver<MrmRequest>> udp_mrm_request_receiver_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::Subscription<tier4_system_msgs::msg::MrmState>::SharedPtr sub_mrm_state_;
rclcpp::Subscription<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr sub_mrm_state_;
rclcpp::Publisher<tier4_system_msgs::msg::MrmBehavior>::SharedPtr pub_mrm_request_;

std::thread udp_receiver_thread_;
Expand Down

0 comments on commit 12da511

Please sign in to comment.