Skip to content

Commit fc26884

Browse files
authored
Merge branch 'beta/v0.3.19' into feat/lane_departure_checker/add_param_footprint_extra_margin
2 parents ba300ce + 15cddc7 commit fc26884

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

42 files changed

+5743
-779
lines changed

common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp

+21
Original file line numberDiff line numberDiff line change
@@ -343,6 +343,27 @@ inline geometry_msgs::msg::Pose calcOffsetPose(
343343
tf2::toMsg(tf_pose * tf_offset, pose);
344344
return pose;
345345
}
346+
347+
/**
348+
* @brief Calculate offset pose. The offset values are defined in the local coordinate of the input
349+
* pose.
350+
*/
351+
inline geometry_msgs::msg::Pose calcOffsetPose(
352+
const geometry_msgs::msg::Pose & p, const double x, const double y, const double z,
353+
const double yaw)
354+
{
355+
geometry_msgs::msg::Pose pose;
356+
geometry_msgs::msg::Transform transform;
357+
transform.translation = createTranslation(x, y, z);
358+
transform.rotation = createQuaternionFromYaw(yaw);
359+
tf2::Transform tf_pose;
360+
tf2::Transform tf_offset;
361+
tf2::fromMsg(transform, tf_offset);
362+
tf2::fromMsg(p, tf_pose);
363+
tf2::toMsg(tf_pose * tf_offset, pose);
364+
return pose;
365+
}
366+
346367
} // namespace tier4_autoware_utils
347368

348369
#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,253 @@
1+
// Copyright 2024 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+
#ifndef TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_
15+
#define TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_
16+
17+
#include <rclcpp/rclcpp.hpp>
18+
19+
#include <memory>
20+
#include <stdexcept>
21+
#include <string>
22+
#include <vector>
23+
24+
namespace autoware::universe_utils
25+
{
26+
27+
/**
28+
* @brief Creates a SensorDataQoS profile with a single depth.
29+
* @return rclcpp::SensorDataQoS The QoS profile with depth set to 1.
30+
*/
31+
inline rclcpp::SensorDataQoS SingleDepthSensorQoS()
32+
{
33+
rclcpp::SensorDataQoS qos;
34+
qos.get_rmw_qos_profile().depth = 1;
35+
return qos;
36+
}
37+
38+
namespace polling_policy
39+
{
40+
41+
/**
42+
* @brief Polling policy that keeps the latest received message.
43+
*
44+
* This policy retains the latest received message and provides it when requested. If a new message
45+
* is received, it overwrites the previously stored message.
46+
*
47+
* @tparam MessageT The message type.
48+
*/
49+
template <typename MessageT>
50+
class Latest
51+
{
52+
private:
53+
typename MessageT::ConstSharedPtr data_{nullptr}; ///< Data pointer to store the latest data
54+
55+
protected:
56+
/**
57+
* @brief Check the QoS settings for the subscription.
58+
*
59+
* @param qos The QoS profile to check.
60+
* @throws std::invalid_argument If the QoS depth is not 1.
61+
*/
62+
void checkQoS(const rclcpp::QoS & qos)
63+
{
64+
if (qos.get_rmw_qos_profile().depth > 1) {
65+
throw std::invalid_argument(
66+
"InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient "
67+
"serialization while updateLatestData()");
68+
}
69+
}
70+
71+
public:
72+
/**
73+
* @brief Retrieve the latest data. If no new data has been received, the previously received data
74+
*
75+
* @return typename MessageT::ConstSharedPtr The latest data.
76+
*/
77+
typename MessageT::ConstSharedPtr takeData();
78+
};
79+
80+
/**
81+
* @brief Polling policy that keeps the newest received message.
82+
*
83+
* @tparam MessageT The message type.
84+
*/
85+
template <typename MessageT>
86+
class Newest
87+
{
88+
protected:
89+
/**
90+
* @brief Check the QoS settings for the subscription.
91+
*
92+
* @param qos The QoS profile to check.
93+
* @throws std::invalid_argument If the QoS depth is not 1.
94+
*/
95+
void checkQoS(const rclcpp::QoS & qos)
96+
{
97+
if (qos.get_rmw_qos_profile().depth > 1) {
98+
throw std::invalid_argument(
99+
"InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient "
100+
"serialization while updateLatestData()");
101+
}
102+
}
103+
104+
public:
105+
/**
106+
* @brief Retrieve the newest data. If no new data has been received, nullptr is returned.
107+
*
108+
* @return typename MessageT::ConstSharedPtr The newest data.
109+
*/
110+
typename MessageT::ConstSharedPtr takeData();
111+
};
112+
113+
/**
114+
* @brief Polling policy that keeps all received messages.
115+
*
116+
* @tparam MessageT The message type.
117+
*/
118+
template <typename MessageT>
119+
class All
120+
{
121+
protected:
122+
/**
123+
* @brief Check the QoS settings for the subscription.
124+
*
125+
* @param qos The QoS profile to check.
126+
*/
127+
void checkQoS(const rclcpp::QoS &) {}
128+
129+
public:
130+
/**
131+
* @brief Retrieve all data.
132+
*
133+
* @return std::vector<typename MessageT::ConstSharedPtr> The list of all received data.
134+
*/
135+
std::vector<typename MessageT::ConstSharedPtr> takeData();
136+
};
137+
138+
} // namespace polling_policy
139+
140+
/**
141+
* @brief Subscriber class that uses a specified polling policy.
142+
*
143+
* @tparam MessageT The message type.
144+
* @tparam PollingPolicy The polling policy to use.
145+
*/
146+
template <typename MessageT, template <typename> class PollingPolicy = polling_policy::Latest>
147+
class InterProcessPollingSubscriber : public PollingPolicy<MessageT>
148+
{
149+
friend PollingPolicy<MessageT>;
150+
151+
private:
152+
typename rclcpp::Subscription<MessageT>::SharedPtr subscriber_; ///< Subscription object
153+
154+
public:
155+
using SharedPtr = std::shared_ptr<InterProcessPollingSubscriber<MessageT, PollingPolicy>>;
156+
157+
/**
158+
* @brief Construct a new InterProcessPollingSubscriber object.
159+
*
160+
* @param node The node to attach the subscriber to.
161+
* @param topic_name The topic name to subscribe to.
162+
* @param qos The QoS profile to use for the subscription.
163+
*/
164+
explicit InterProcessPollingSubscriber(
165+
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1})
166+
{
167+
this->checkQoS(qos);
168+
169+
auto noexec_callback_group =
170+
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
171+
172+
auto noexec_subscription_options = rclcpp::SubscriptionOptions();
173+
noexec_subscription_options.callback_group = noexec_callback_group;
174+
175+
subscriber_ = node->create_subscription<MessageT>(
176+
topic_name, qos,
177+
[node]([[maybe_unused]] const typename MessageT::ConstSharedPtr msg) { assert(false); },
178+
noexec_subscription_options);
179+
}
180+
181+
/**
182+
* @brief Create a subscription.
183+
*
184+
* @param node The node to attach the subscriber to.
185+
* @param topic_name The topic name to subscribe to.
186+
* @param qos The QoS profile to use for the subscription.
187+
* @return SharedPtr The created subscription.
188+
*/
189+
static SharedPtr create_subscription(
190+
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1})
191+
{
192+
return std::make_shared<InterProcessPollingSubscriber<MessageT, PollingPolicy>>(
193+
node, topic_name, qos);
194+
}
195+
196+
typename rclcpp::Subscription<MessageT>::SharedPtr subscriber() { return subscriber_; }
197+
};
198+
199+
namespace polling_policy
200+
{
201+
202+
template <typename MessageT>
203+
typename MessageT::ConstSharedPtr Latest<MessageT>::takeData()
204+
{
205+
auto & subscriber =
206+
static_cast<InterProcessPollingSubscriber<MessageT, Latest> *>(this)->subscriber_;
207+
auto new_data = std::make_shared<MessageT>();
208+
rclcpp::MessageInfo message_info;
209+
const bool success = subscriber->take(*new_data, message_info);
210+
if (success) {
211+
data_ = new_data;
212+
}
213+
214+
return data_;
215+
}
216+
217+
template <typename MessageT>
218+
typename MessageT::ConstSharedPtr Newest<MessageT>::takeData()
219+
{
220+
auto & subscriber =
221+
static_cast<InterProcessPollingSubscriber<MessageT, Newest> *>(this)->subscriber_;
222+
auto new_data = std::make_shared<MessageT>();
223+
rclcpp::MessageInfo message_info;
224+
const bool success = subscriber->take(*new_data, message_info);
225+
if (success) {
226+
return new_data;
227+
}
228+
return nullptr;
229+
}
230+
231+
template <typename MessageT>
232+
std::vector<typename MessageT::ConstSharedPtr> All<MessageT>::takeData()
233+
{
234+
auto & subscriber =
235+
static_cast<InterProcessPollingSubscriber<MessageT, All> *>(this)->subscriber_;
236+
std::vector<typename MessageT::ConstSharedPtr> data;
237+
rclcpp::MessageInfo message_info;
238+
for (;;) {
239+
auto datum = std::make_shared<MessageT>();
240+
if (subscriber->take(*datum, message_info)) {
241+
data.push_back(datum);
242+
} else {
243+
break;
244+
}
245+
}
246+
return data;
247+
}
248+
249+
} // namespace polling_policy
250+
251+
} // namespace autoware::universe_utils
252+
253+
#endif // TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_

common/tier4_autoware_utils/include/tier4_autoware_utils/tier4_autoware_utils.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include "tier4_autoware_utils/ros/debug_publisher.hpp"
2828
#include "tier4_autoware_utils/ros/debug_traits.hpp"
2929
#include "tier4_autoware_utils/ros/marker_helper.hpp"
30+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
3031
#include "tier4_autoware_utils/ros/processing_time_publisher.hpp"
3132
#include "tier4_autoware_utils/ros/self_pose_listener.hpp"
3233
#include "tier4_autoware_utils/ros/transform_listener.hpp"

control/autonomous_emergency_braking/CMakeLists.txt

-26
This file was deleted.

control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml

-17
This file was deleted.

0 commit comments

Comments
 (0)