Skip to content

Commit 53e43a2

Browse files
committed
modify: precommit
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
2 parents 8cf97b3 + 4abddaa commit 53e43a2

13 files changed

+195
-160
lines changed

system/leader_election_converter/README.md

+21-23
Original file line numberDiff line numberDiff line change
@@ -8,45 +8,43 @@ The leader election converter node is responsible for relaying UDP packets and R
88

99
The availability converter subscribes `/system/operation_mode/availability` and `/vehicle/status/mrm_state`, adds them together into a structure called `Availability` and sends it as a udp packet.
1010

11-
1211
### Interface
1312

14-
| Interface Type | Interface Name | Data Type | Description |
15-
| -------------- | ------------------------------------- | ------------------------------------------------- | ---------------------------------- |
16-
| subscriber | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | Usable behavior of the ego. |
17-
| subscriber | `/vehicle/status/mrm_state` | `autoware_auto_vehicle_msgs/msg/ControlModeReport`| Ego control mode. |
18-
| udp sender | none | `struct Availability` | Combination of the above two. |
19-
13+
| Interface Type | Interface Name | Data Type | Description |
14+
| -------------- | ------------------------------------- | -------------------------------------------------- | ----------------------------- |
15+
| subscriber | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | Usable behavior of the ego. |
16+
| subscriber | `/vehicle/status/mrm_state` | `autoware_auto_vehicle_msgs/msg/ControlModeReport` | Ego control mode. |
17+
| udp sender | none | `struct Availability` | Combination of the above two. |
2018

2119
## mrm converte
20+
2221
The mrm converter subscribes `/system/fail_safe/mrm_state` into a structure called `MrmState` and sends it as a UDP packet.
2322
In addition, it receives a udp packet`MrmState` and publish `/system/mrm_request`.
2423

2524
### Interface
2625

27-
| Interface Type | Interface Name | Data Type | Description |
28-
| -------------- | ------------------------------------- | ------------------------------------------------- | ---------------------------------- |
29-
| subscriber | `/system/fail_safe/mrm_state` | `tier4_system_msgs/msg/MrmState` | MRM status of each ECU. |
30-
| udp sender | none | `struct MrmState` | Same as above. |
31-
| publisher | `/system/election/mrm_request` | `tier4_system_msgs/msg/MrmBehavior` | Request of MRM behavior. |
32-
| udp receiver | none | `struct MrmRequest` | Same as above. |
33-
26+
| Interface Type | Interface Name | Data Type | Description |
27+
| -------------- | ------------------------------ | ----------------------------------- | ------------------------ |
28+
| subscriber | `/system/fail_safe/mrm_state` | `tier4_system_msgs/msg/MrmState` | MRM status of each ECU. |
29+
| udp sender | none | `struct MrmState` | Same as above. |
30+
| publisher | `/system/election/mrm_request` | `tier4_system_msgs/msg/MrmBehavior` | Request of MRM behavior. |
31+
| udp receiver | none | `struct MrmRequest` | Same as above. |
3432

3533
## log converter
36-
The log converter receive udp packets into a structure called `ElectionCommunication` and `ElectionStatus`, and publish `/system/election/communication`,
34+
35+
The log converter receive udp packets into a structure called `ElectionCommunication` and `ElectionStatus`, and publish `/system/election/communication`,
3736
`/system/election/status`, and `/system/fail_safe/over_all/mrm_state`.
3837

3938
### Interface
4039

41-
| Interface Type | Interface Name | Data Type | Description |
42-
| -------------- | ------------------------------------- | ------------------------------------------------- | ---------------------------------- |
43-
| udp receiver | none | `struct ElectionCommunication` | messages amoung election nodes. |
44-
| udp receiver | none | `struct ElectionStatus` | Leader Election status. |
45-
| publisher | `/system/election/communication` | `tier4_system_msgs/msg/ElectionCommunication` | messages amoung election nodes. |
46-
| publisher | `/system/election/status` | `tier4_system_msgs/msg/MrmState` | Leader Election status. |
47-
| publisher | `/system/fail_safe/over_all/mrm_state`| `autoware_adapi_v1_msgs/msg/mrm_state` | System-wode MRM status. |
40+
| Interface Type | Interface Name | Data Type | Description |
41+
| -------------- | -------------------------------------- | --------------------------------------------- | ------------------------------- |
42+
| udp receiver | none | `struct ElectionCommunication` | messages amoung election nodes. |
43+
| udp receiver | none | `struct ElectionStatus` | Leader Election status. |
44+
| publisher | `/system/election/communication` | `tier4_system_msgs/msg/ElectionCommunication` | messages amoung election nodes. |
45+
| publisher | `/system/election/status` | `tier4_system_msgs/msg/MrmState` | Leader Election status. |
46+
| publisher | `/system/fail_safe/over_all/mrm_state` | `autoware_adapi_v1_msgs/msg/mrm_state` | System-wode MRM status. |
4847

4948
## Parameters
5049

5150
{{ json_to_markdown("system/leader_election_converter/schema/leader_election_converter.schema.json") }}
52-

system/leader_election_converter/launch/leader_election_converter.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
<launch>
1+
<launch>
22
<arg name="param_file" default="$(find-pkg-share leader_election_converter)/config/leader_electioin_converter.param.yaml"/>
33
<arg name="input_control_mode" default="/vehicle/status/control_mode"/>
44
<arg name="input_operation_mode_availability" default="/system/operation_mode/availability"/>

system/leader_election_converter/package.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,11 @@
1010
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212

13+
<depend>autoware_adapi_v1_msgs</depend>
14+
<depend>autoware_auto_vehicle_msgs</depend>
1315
<depend>rclcpp</depend>
1416
<depend>rclcpp_components</depend>
1517
<depend>tier4_system_msgs</depend>
16-
<depend>autoware_auto_vehicle_msgs</depend>
17-
<depend>autoware_adapi_v1_msgs</depend>
1818

1919
<test_depend>ament_lint_auto</test_depend>
2020
<test_depend>autoware_lint_common</test_depend>

system/leader_election_converter/src/common/converter/availability_converter.cpp

+19-13
Original file line numberDiff line numberDiff line change
@@ -14,15 +14,16 @@
1414

1515
#include <string>
1616
#include <memory>
17+
#include "availability_converter.hpp"
1718

1819
#include "rclcpp/rclcpp.hpp"
19-
#include "availability_converter.hpp"
2020

2121
namespace leader_election_converter
2222
{
2323

24-
AvailabilityConverter::AvailabilityConverter(rclcpp::Node * node)
25-
: node_(node) {}
24+
AvailabilityConverter::AvailabilityConverter(rclcpp::Node * node) : node_(node)
25+
{
26+
}
2627

2728
void AvailabilityConverter::setUdpSender(const std::string & dest_ip, const std::string & dest_port)
2829
{
@@ -32,22 +33,27 @@ void AvailabilityConverter::setUdpSender(const std::string & dest_ip, const std:
3233
void AvailabilityConverter::setSubscriber()
3334
{
3435
const auto qos = rclcpp::QoS(1).transient_local();
35-
availability_callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
36+
availability_callback_group_ =
37+
node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
3638
rclcpp::SubscriptionOptions availability_options = rclcpp::SubscriptionOptions();
3739
availability_options.callback_group = availability_callback_group_;
3840

39-
control_mode_callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
41+
control_mode_callback_group_ =
42+
node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
4043
rclcpp::SubscriptionOptions control_mode_options = rclcpp::SubscriptionOptions();
41-
control_mode_options.callback_group = control_mode_callback_group_;
42-
auto not_executed_callback = []([[maybe_unused]] const typename autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) {};
44+
control_mode_options.callback_group = control_mode_callback_group_;
45+
auto not_executed_callback = []([[maybe_unused]] const typename autoware_auto_vehicle_msgs::msg::
46+
ControlModeReport::ConstSharedPtr msg) {};
4347

44-
sub_operation_mode_availability_ = node_->create_subscription<tier4_system_msgs::msg::OperationModeAvailability>(
45-
"~/input/operation_mode_availability", qos,
46-
std::bind(&AvailabilityConverter::convertToUdp, this, std::placeholders::_1), availability_options);
48+
sub_operation_mode_availability_ =
49+
node_->create_subscription<tier4_system_msgs::msg::OperationModeAvailability>(
50+
"~/input/operation_mode_availability", qos,
51+
std::bind(&AvailabilityConverter::convertToUdp, this, std::placeholders::_1),
52+
availability_options);
4753

48-
sub_control_mode_ = node_->create_subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>(
49-
"~/input/control_mode", qos, not_executed_callback, control_mode_options);
50-
54+
sub_control_mode_ =
55+
node_->create_subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>(
56+
"~/input/control_mode", qos, not_executed_callback, control_mode_options);
5157
}
5258

5359
void AvailabilityConverter::convertToUdp(

system/leader_election_converter/src/common/converter/availability_converter.hpp

+11-9
Original file line numberDiff line numberDiff line change
@@ -48,18 +48,20 @@ class AvailabilityConverter
4848

4949
void setUdpSender(const std::string & dest_ip, const std::string & dest_port);
5050
void setSubscriber();
51-
void convertToUdp(const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr availability_msg);
51+
void convertToUdp(
52+
const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr availability_msg);
5253

5354
private:
54-
rclcpp::Node * node_;
55-
std::unique_ptr<UdpSender<Availability>> udp_availability_sender_;
56-
rclcpp::CallbackGroup::SharedPtr availability_callback_group_;
57-
rclcpp::CallbackGroup::SharedPtr control_mode_callback_group_;
58-
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr sub_control_mode_;
59-
rclcpp::Subscription<tier4_system_msgs::msg::OperationModeAvailability>::SharedPtr sub_operation_mode_availability_;
60-
55+
rclcpp::Node * node_;
56+
std::unique_ptr<UdpSender<Availability>> udp_availability_sender_;
57+
rclcpp::CallbackGroup::SharedPtr availability_callback_group_;
58+
rclcpp::CallbackGroup::SharedPtr control_mode_callback_group_;
59+
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
60+
sub_control_mode_;
61+
rclcpp::Subscription<tier4_system_msgs::msg::OperationModeAvailability>::SharedPtr
62+
sub_operation_mode_availability_;
6163
};
6264

6365
} // namespace leader_election_converter
6466

65-
#endif // COMMON__AVAILABILITY_CONVERTER_HPP_
67+
#endif // COMMON__CONVERTER__AVAILABILITY_CONVERTER_HPP_

system/leader_election_converter/src/common/converter/log_converter.cpp

+26-14
Original file line numberDiff line numberDiff line change
@@ -18,14 +18,15 @@
1818
#include "rclcpp/rclcpp.hpp"
1919
#include "log_converter.hpp"
2020

21+
#include "rclcpp/rclcpp.hpp"
22+
2123
namespace leader_election_converter
2224
{
2325

2426
LogConverter::LogConverter(rclcpp::Node * node)
25-
: node_(node),
26-
is_election_comunication_running_(true),
27-
is_election_status_running_(true)
28-
{}
27+
: node_(node), is_election_comunication_running_(true), is_election_status_running_(true)
28+
{
29+
}
2930

3031
LogConverter::~LogConverter()
3132
{
@@ -41,15 +42,20 @@ LogConverter::~LogConverter()
4142
}
4243
}
4344

44-
void LogConverter::setUdpElectionCommunicatioinReceiver(const std::string & src_ip, const std::string & src_port)
45+
void LogConverter::setUdpElectionCommunicatioinReceiver(
46+
const std::string & src_ip, const std::string & src_port)
4547
{
46-
udp_election_comunication_thread_ = std::thread(&LogConverter::startUdpElectionCommunicationReceiver, this, src_ip, src_port);
48+
udp_election_comunication_thread_ =
49+
std::thread(&LogConverter::startUdpElectionCommunicationReceiver, this, src_ip, src_port);
4750
}
4851

49-
void LogConverter::startUdpElectionCommunicationReceiver(const std::string & src_ip, const std::string & src_port)
52+
void LogConverter::startUdpElectionCommunicationReceiver(
53+
const std::string & src_ip, const std::string & src_port)
5054
{
5155
try {
52-
udp_election_comunication_receiver_ = std::make_unique<UdpReceiver<ElectionCommunication>>(src_ip, src_port, std::bind(&LogConverter::convertElectionCommunicationToTopic, this, std::placeholders::_1));
56+
udp_election_comunication_receiver_ = std::make_unique<UdpReceiver<ElectionCommunication>>(
57+
src_ip, src_port,
58+
std::bind(&LogConverter::convertElectionCommunicationToTopic, this, std::placeholders::_1));
5359
while (is_election_comunication_running_) {
5460
udp_election_comunication_receiver_->receive();
5561
}
@@ -58,15 +64,20 @@ void LogConverter::startUdpElectionCommunicationReceiver(const std::string & src
5864
}
5965
}
6066

61-
void LogConverter::setUdpElectionStatusReceiver(const std::string & src_ip, const std::string & src_port)
67+
void LogConverter::setUdpElectionStatusReceiver(
68+
const std::string & src_ip, const std::string & src_port)
6269
{
63-
udp_election_status_thread_ = std::thread(&LogConverter::startUdpElectionStatusReceiver, this, src_ip, src_port);
70+
udp_election_status_thread_ =
71+
std::thread(&LogConverter::startUdpElectionStatusReceiver, this, src_ip, src_port);
6472
}
6573

66-
void LogConverter::startUdpElectionStatusReceiver(const std::string & src_ip, const std::string & src_port)
74+
void LogConverter::startUdpElectionStatusReceiver(
75+
const std::string & src_ip, const std::string & src_port)
6776
{
6877
try {
69-
udp_election_status_receiver_ = std::make_unique<UdpReceiver<ElectionStatus>>(src_ip, src_port, std::bind(&LogConverter::convertElectionStatusToTopic, this, std::placeholders::_1));
78+
udp_election_status_receiver_ = std::make_unique<UdpReceiver<ElectionStatus>>(
79+
src_ip, src_port,
80+
std::bind(&LogConverter::convertElectionStatusToTopic, this, std::placeholders::_1));
7081
while (is_election_status_running_) {
7182
udp_election_status_receiver_->receive();
7283
}
@@ -77,8 +88,9 @@ void LogConverter::startUdpElectionStatusReceiver(const std::string & src_ip, co
7788

7889
void LogConverter::setPublisher()
7990
{
80-
pub_election_comunication_ = node_->create_publisher<tier4_system_msgs::msg::ElectionCommunication>(
81-
"~/output/election_communication", rclcpp::QoS{1});
91+
pub_election_comunication_ =
92+
node_->create_publisher<tier4_system_msgs::msg::ElectionCommunication>(
93+
"~/output/election_communication", rclcpp::QoS{1});
8294
pub_election_status_ = node_->create_publisher<tier4_system_msgs::msg::ElectionStatus>(
8395
"~/output/election_status", rclcpp::QoS{1});
8496
pub_over_all_mrm_state_ = node_->create_publisher<autoware_adapi_v1_msgs::msg::MrmState>(

system/leader_election_converter/src/common/converter/log_converter.hpp

+16-10
Original file line numberDiff line numberDiff line change
@@ -12,24 +12,27 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef COMMON__LOG_CONVERTER_HPP_
16-
#define COMMON__LOG_CONVERTER_HPP_
15+
#ifndef COMMON__CONVERTER__LOG_CONVERTER_HPP_
16+
#define COMMON__CONVERTER__LOG_CONVERTER_HPP_
1717

18+
#include "udp_receiver.hpp"
19+
#include "udp_sender.hpp"
20+
21+
#include <rclcpp/rclcpp.hpp>
22+
23+
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
1824
#include <tier4_system_msgs/msg/election_communication.hpp>
1925
#include <tier4_system_msgs/msg/election_status.hpp>
2026
#include <tier4_system_msgs/msg/mrm_state.hpp>
21-
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
2227

23-
#include <rclcpp/rclcpp.hpp>
24-
#include <thread>
2528
#include <atomic>
2629
#include <memory>
2730
#include <string>
31+
#include <thread>
2832

2933
#include "udp_sender.hpp"
3034
#include "udp_receiver.hpp"
3135

32-
3336
namespace leader_election_converter
3437
{
3538

@@ -61,20 +64,23 @@ class LogConverter
6164
explicit LogConverter(rclcpp::Node * node);
6265
~LogConverter();
6366

64-
void setUdpElectionCommunicatioinReceiver(const std::string & src_ip, const std::string & src_port);
67+
void setUdpElectionCommunicatioinReceiver(
68+
const std::string & src_ip, const std::string & src_port);
6569
void setUdpElectionStatusReceiver(const std::string & src_ip, const std::string & src_port);
6670
void setPublisher();
6771

6872
private:
69-
void startUdpElectionCommunicationReceiver(const std::string & src_ip, const std::string & src_port);
73+
void startUdpElectionCommunicationReceiver(
74+
const std::string & src_ip, const std::string & src_port);
7075
void startUdpElectionStatusReceiver(const std::string & src_ip, const std::string & src_port);
7176
void convertElectionCommunicationToTopic(const ElectionCommunication & node_msg);
7277
void convertElectionStatusToTopic(const ElectionStatus & status);
7378

7479
rclcpp::Node * node_;
7580
std::unique_ptr<UdpReceiver<ElectionCommunication>> udp_election_comunication_receiver_;
7681
std::unique_ptr<UdpReceiver<ElectionStatus>> udp_election_status_receiver_;
77-
rclcpp::Publisher<tier4_system_msgs::msg::ElectionCommunication>::SharedPtr pub_election_comunication_;
82+
rclcpp::Publisher<tier4_system_msgs::msg::ElectionCommunication>::SharedPtr
83+
pub_election_comunication_;
7884
rclcpp::Publisher<tier4_system_msgs::msg::ElectionStatus>::SharedPtr pub_election_status_;
7985
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_over_all_mrm_state_;
8086

@@ -86,4 +92,4 @@ class LogConverter
8692

8793
} // namespace leader_election_converter
8894

89-
#endif // COMMON__LOG_CONVERTER_HPP_
95+
#endif // COMMON__CONVERTER__LOG_CONVERTER_HPP_

system/leader_election_converter/src/common/converter/mrm_converter.cpp

+9-7
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,12 @@
1818
#include "rclcpp/rclcpp.hpp"
1919
#include "mrm_converter.hpp"
2020

21+
#include "rclcpp/rclcpp.hpp"
22+
2123
namespace leader_election_converter
2224
{
2325

24-
MrmConverter::MrmConverter(rclcpp::Node * node)
25-
: node_(node),
26-
is_udp_receiver_running_(true)
26+
MrmConverter::MrmConverter(rclcpp::Node * node) : node_(node), is_udp_receiver_running_(true)
2727
{
2828
}
2929

@@ -49,7 +49,8 @@ void MrmConverter::setUdpReceiver(const std::string & src_ip, const std::string
4949
void MrmConverter::startUdpReceiver(const std::string & src_ip, const std::string & src_port)
5050
{
5151
try {
52-
udp_mrm_request_receiver_ = std::make_unique<UdpReceiver<MrmRequest>>(src_ip, src_port, std::bind(&MrmConverter::convertToTopic, this, std::placeholders::_1));
52+
udp_mrm_request_receiver_ = std::make_unique<UdpReceiver<MrmRequest>>(
53+
src_ip, src_port, std::bind(&MrmConverter::convertToTopic, this, std::placeholders::_1));
5354
while (is_udp_receiver_running_) {
5455
udp_mrm_request_receiver_->receive();
5556
}
@@ -66,8 +67,8 @@ void MrmConverter::setSubscriber()
6667
options.callback_group = callback_group_;
6768

6869
sub_mrm_state_ = node_->create_subscription<tier4_system_msgs::msg::MrmState>(
69-
"~/input/mrm_state", qos,
70-
std::bind(&MrmConverter::convertToUdp, this, std::placeholders::_1), options);
70+
"~/input/mrm_state", qos, std::bind(&MrmConverter::convertToUdp, this, std::placeholders::_1),
71+
options);
7172
}
7273

7374
void MrmConverter::setPublisher()
@@ -76,7 +77,8 @@ void MrmConverter::setPublisher()
7677
"~/output/mrm_request", rclcpp::QoS{1});
7778
}
7879

79-
void MrmConverter::convertToUdp(const tier4_system_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg)
80+
void MrmConverter::convertToUdp(
81+
const tier4_system_msgs::msg::MrmState::ConstSharedPtr mrm_state_msg)
8082
{
8183
MrmState mrm_state;
8284
mrm_state.state = mrm_state_msg->state;

0 commit comments

Comments
 (0)