Skip to content

Commit c75a8eb

Browse files
authored
feat: add marker of cmd gate filter (autowarefoundation#4741)
* feat: add marker of cmd gate filter Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> * feat: add sphere marker Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> * misc Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> --------- Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp>
1 parent eadfa78 commit c75a8eb

File tree

4 files changed

+178
-0
lines changed

4 files changed

+178
-0
lines changed

control/vehicle_cmd_gate/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
<depend>tier4_system_msgs</depend>
3535
<depend>tier4_vehicle_msgs</depend>
3636
<depend>vehicle_info_util</depend>
37+
<depend>visualization_msgs</depend>
3738

3839
<exec_depend>rosidl_default_runtime</exec_depend>
3940

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,119 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef MARKER_HELPER_HPP_
16+
#define MARKER_HELPER_HPP_
17+
18+
#include <rclcpp/rclcpp.hpp>
19+
20+
#include <visualization_msgs/msg/marker_array.hpp>
21+
22+
#include <string>
23+
24+
namespace vehicle_cmd_gate
25+
{
26+
inline geometry_msgs::msg::Point createMarkerPosition(double x, double y, double z)
27+
{
28+
geometry_msgs::msg::Point point;
29+
30+
point.x = x;
31+
point.y = y;
32+
point.z = z;
33+
34+
return point;
35+
}
36+
37+
inline geometry_msgs::msg::Quaternion createMarkerOrientation(
38+
double x, double y, double z, double w)
39+
{
40+
geometry_msgs::msg::Quaternion quaternion;
41+
42+
quaternion.x = x;
43+
quaternion.y = y;
44+
quaternion.z = z;
45+
quaternion.w = w;
46+
47+
return quaternion;
48+
}
49+
50+
inline geometry_msgs::msg::Vector3 createMarkerScale(double x, double y, double z)
51+
{
52+
geometry_msgs::msg::Vector3 scale;
53+
54+
scale.x = x;
55+
scale.y = y;
56+
scale.z = z;
57+
58+
return scale;
59+
}
60+
61+
inline std_msgs::msg::ColorRGBA createMarkerColor(float r, float g, float b, float a)
62+
{
63+
std_msgs::msg::ColorRGBA color;
64+
65+
color.r = r;
66+
color.g = g;
67+
color.b = b;
68+
color.a = a;
69+
70+
return color;
71+
}
72+
73+
inline visualization_msgs::msg::Marker createMarker(
74+
const std::string & frame_id, const std::string & ns, const int32_t id, const int32_t type,
75+
geometry_msgs::msg::Point point, geometry_msgs::msg::Vector3 scale,
76+
const std_msgs::msg::ColorRGBA & color)
77+
{
78+
visualization_msgs::msg::Marker marker;
79+
80+
marker.header.frame_id = frame_id;
81+
marker.header.stamp = rclcpp::Time(0);
82+
marker.ns = ns;
83+
marker.id = id;
84+
marker.type = type;
85+
marker.action = visualization_msgs::msg::Marker::ADD;
86+
marker.lifetime = rclcpp::Duration::from_seconds(0.2);
87+
marker.pose.position = point;
88+
marker.pose.orientation = createMarkerOrientation(0.0, 0.0, 0.0, 1.0);
89+
marker.scale = scale;
90+
marker.color = color;
91+
marker.frame_locked = false;
92+
93+
return marker;
94+
}
95+
96+
inline visualization_msgs::msg::Marker createStringMarker(
97+
const std::string & frame_id, const std::string & ns, const int32_t id, const int32_t type,
98+
geometry_msgs::msg::Point point, geometry_msgs::msg::Vector3 scale,
99+
const std_msgs::msg::ColorRGBA & color, const std::string text)
100+
{
101+
visualization_msgs::msg::Marker marker;
102+
103+
marker = createMarker(frame_id, ns, id, type, point, scale, color);
104+
marker.text = text;
105+
106+
return marker;
107+
}
108+
109+
inline void appendMarkerArray(
110+
const visualization_msgs::msg::MarkerArray & additional_marker_array,
111+
visualization_msgs::msg::MarkerArray * marker_array)
112+
{
113+
for (const auto & marker : additional_marker_array.markers) {
114+
marker_array->markers.push_back(marker);
115+
}
116+
}
117+
} // namespace vehicle_cmd_gate
118+
119+
#endif // MARKER_HELPER_HPP_

control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+52
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
#include "vehicle_cmd_gate.hpp"
1616

17+
#include "marker_helper.hpp"
18+
1719
#include <rclcpp/logging.hpp>
1820
#include <tier4_api_utils/tier4_api_utils.hpp>
1921

@@ -73,6 +75,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
7375

7476
is_filter_activated_pub_ =
7577
create_publisher<IsFilterActivated>("~/is_filter_activated", durable_qos);
78+
filter_activated_marker_pub_ =
79+
create_publisher<MarkerArray>("~/is_filter_activated/marker", durable_qos);
7680

7781
// Subscriber
7882
external_emergency_stop_heartbeat_sub_ = create_subscription<Heartbeat>(
@@ -564,6 +568,7 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont
564568

565569
is_filter_activated.stamp = now();
566570
is_filter_activated_pub_->publish(is_filter_activated);
571+
filter_activated_marker_pub_->publish(createMarkerArray(is_filter_activated));
567572

568573
return out;
569574
}
@@ -731,6 +736,53 @@ void VehicleCmdGate::checkExternalEmergencyStop(diagnostic_updater::DiagnosticSt
731736
stat.summary(status.level, status.message);
732737
}
733738

739+
MarkerArray VehicleCmdGate::createMarkerArray(const IsFilterActivated & filter_activated)
740+
{
741+
MarkerArray msg;
742+
743+
if (!filter_activated.is_activated) {
744+
return msg;
745+
}
746+
747+
/* add string marker */
748+
bool first_msg = true;
749+
std::string reason = "filter activated on";
750+
751+
if (filter_activated.is_activated_on_acceleration) {
752+
reason += " lon_acc";
753+
first_msg = false;
754+
}
755+
if (filter_activated.is_activated_on_jerk) {
756+
reason += first_msg ? " jerk" : ", jerk";
757+
first_msg = false;
758+
}
759+
if (filter_activated.is_activated_on_speed) {
760+
reason += first_msg ? " speed" : ", speed";
761+
first_msg = false;
762+
}
763+
if (filter_activated.is_activated_on_steering) {
764+
reason += first_msg ? " steer" : ", steer";
765+
first_msg = false;
766+
}
767+
if (filter_activated.is_activated_on_steering_rate) {
768+
reason += first_msg ? " steer_rate" : ", steer_rate";
769+
first_msg = false;
770+
}
771+
772+
msg.markers.emplace_back(createStringMarker(
773+
"base_link", "msg", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING,
774+
createMarkerPosition(0.0, 0.0, 1.0), createMarkerScale(0.0, 0.0, 1.0),
775+
createMarkerColor(1.0, 0.0, 0.0, 1.0), reason));
776+
777+
/* add sphere marker */
778+
msg.markers.emplace_back(createMarker(
779+
"base_link", "sphere", 0, visualization_msgs::msg::Marker::SPHERE,
780+
createMarkerPosition(0.0, 0.0, 0.0), createMarkerScale(3.0, 3.0, 3.0),
781+
createMarkerColor(1.0, 0.0, 0.0, 0.3)));
782+
783+
return msg;
784+
}
785+
734786
} // namespace vehicle_cmd_gate
735787

736788
#include <rclcpp_components/register_node_macro.hpp>

control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include <tier4_external_api_msgs/srv/set_emergency.hpp>
4545
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
4646
#include <tier4_vehicle_msgs/msg/vehicle_emergency_stamped.hpp>
47+
#include <visualization_msgs/msg/marker_array.hpp>
4748

4849
#include <memory>
4950

@@ -66,6 +67,7 @@ using tier4_external_api_msgs::srv::SetEmergency;
6667
using tier4_system_msgs::msg::MrmBehaviorStatus;
6768
using tier4_vehicle_msgs::msg::VehicleEmergencyStamped;
6869
using vehicle_cmd_gate::msg::IsFilterActivated;
70+
using visualization_msgs::msg::MarkerArray;
6971

7072
using diagnostic_msgs::msg::DiagnosticStatus;
7173
using nav_msgs::msg::Odometry;
@@ -102,6 +104,7 @@ class VehicleCmdGate : public rclcpp::Node
102104
rclcpp::Publisher<EngageMsg>::SharedPtr engage_pub_;
103105
rclcpp::Publisher<OperationModeState>::SharedPtr operation_mode_pub_;
104106
rclcpp::Publisher<IsFilterActivated>::SharedPtr is_filter_activated_pub_;
107+
rclcpp::Publisher<MarkerArray>::SharedPtr filter_activated_marker_pub_;
105108

106109
// Subscription
107110
rclcpp::Subscription<Heartbeat>::SharedPtr external_emergency_stop_heartbeat_sub_;
@@ -229,6 +232,9 @@ class VehicleCmdGate : public rclcpp::Node
229232
// stop checker
230233
std::unique_ptr<VehicleStopChecker> vehicle_stop_checker_;
231234
double stop_check_duration_;
235+
236+
// debug
237+
MarkerArray createMarkerArray(const IsFilterActivated & filter_activated);
232238
};
233239

234240
} // namespace vehicle_cmd_gate

0 commit comments

Comments
 (0)