Skip to content

Commit 9d55420

Browse files
committed
update param for 3 lidar bag
temp
1 parent 9e62a63 commit 9d55420

File tree

3 files changed

+40
-26
lines changed

3 files changed

+40
-26
lines changed

tools/reaction_analyzer/include/reaction_analyzer_node.hpp

+35-20
Original file line numberDiff line numberDiff line change
@@ -159,22 +159,27 @@ template <typename T>
159159
struct PublisherVariablesMessageTypeExtractor;
160160

161161
template <typename MessageType>
162-
struct PublisherVariablesMessageTypeExtractor<PublisherVariables<MessageType>> {
162+
struct PublisherVariablesMessageTypeExtractor<PublisherVariables<MessageType>>
163+
{
163164
using Type = MessageType;
164165
};
165166

166-
template<typename T, typename = std::void_t<>>
167-
struct has_header : std::false_type {};
168-
169-
template<typename T>
170-
struct has_header<T, std::void_t<decltype(T::header)>> : std::true_type {};
171-
167+
template <typename T, typename = std::void_t<>>
168+
struct has_header : std::false_type
169+
{
170+
};
172171

173-
struct PublisherVarAccessor {
172+
template <typename T>
173+
struct has_header<T, std::void_t<decltype(T::header)>> : std::true_type
174+
{
175+
};
174176

177+
struct PublisherVarAccessor
178+
{
175179
// Method to set header time if available
176180
template <typename T>
177-
void setHeaderTimeIfAvailable(T& publisherVar, const rclcpp::Time& time) {
181+
void setHeaderTimeIfAvailable(T & publisherVar, const rclcpp::Time & time)
182+
{
178183
if constexpr (has_header<typename T::MessageType>::value) {
179184
if (publisherVar.empty_area_message) {
180185
publisherVar.empty_area_message->header.stamp = time;
@@ -187,66 +192,76 @@ struct PublisherVarAccessor {
187192

188193
// Set Period
189194
template <typename T>
190-
void setPeriod(T& publisherVar, double newPeriod) {
195+
void setPeriod(T & publisherVar, double newPeriod)
196+
{
191197
publisherVar.period_ns = newPeriod;
192198
}
193199

194200
// Get Period
195201
template <typename T>
196-
double getPeriod(const T& publisherVar) const {
202+
double getPeriod(const T & publisherVar) const
203+
{
197204
return publisherVar.period_ns;
198205
}
199206

200207
// Set Empty Area Message
201208
template <typename T, typename Message>
202-
void setEmptyAreaMessage(T& publisherVar, typename Message::SharedPtr message) {
209+
void setEmptyAreaMessage(T & publisherVar, typename Message::SharedPtr message)
210+
{
203211
publisherVar.empty_area_message = message;
204212
}
205213

206214
// Get Empty Area Message
207215
template <typename T>
208-
std::shared_ptr<void> getEmptyAreaMessage(const T& publisherVar) const {
216+
std::shared_ptr<void> getEmptyAreaMessage(const T & publisherVar) const
217+
{
209218
return std::static_pointer_cast<void>(publisherVar.empty_area_message);
210219
}
211220

212221
// Set Object Spawned Message
213222
template <typename T, typename Message>
214-
void setObjectSpawnedMessage(T& publisherVar, typename Message::SharedPtr message) {
223+
void setObjectSpawnedMessage(T & publisherVar, typename Message::SharedPtr message)
224+
{
215225
publisherVar.object_spawned_message = message;
216226
}
217227

218228
// Get Object Spawned Message
219229
template <typename T>
220-
std::shared_ptr<void> getObjectSpawnedMessage(const T& publisherVar) const {
230+
std::shared_ptr<void> getObjectSpawnedMessage(const T & publisherVar) const
231+
{
221232
return std::static_pointer_cast<void>(publisherVar.object_spawned_message);
222233
}
223234

224235
// Set Publisher
225236
template <typename T, typename PublisherType>
226-
void setPublisher(T& publisherVar, typename rclcpp::Publisher<PublisherType>::SharedPtr publisher) {
237+
void setPublisher(
238+
T & publisherVar, typename rclcpp::Publisher<PublisherType>::SharedPtr publisher)
239+
{
227240
publisherVar.publisher = publisher;
228241
}
229242

230243
// Get Publisher
231244
template <typename T>
232-
std::shared_ptr<void> getPublisher(const T& publisherVar) const {
245+
std::shared_ptr<void> getPublisher(const T & publisherVar) const
246+
{
233247
return std::static_pointer_cast<void>(publisherVar.publisher);
234248
}
235249

236250
// Set Timer
237251
template <typename T>
238-
void setTimer(T& publisherVar, rclcpp::TimerBase::SharedPtr newTimer) {
252+
void setTimer(T & publisherVar, rclcpp::TimerBase::SharedPtr newTimer)
253+
{
239254
publisherVar.timer = newTimer;
240255
}
241256

242257
// Get Timer
243258
template <typename T>
244-
std::shared_ptr<void> getTimer(const T& publisherVar) const {
259+
std::shared_ptr<void> getTimer(const T & publisherVar) const
260+
{
245261
return std::static_pointer_cast<void>(publisherVar.timer);
246262
}
247263
};
248264

249-
250265
using PublisherVariablesVariant = std::variant<
251266
PublisherVariables<PointCloud2>, PublisherVariables<sensor_msgs::msg::CameraInfo>,
252267
PublisherVariables<sensor_msgs::msg::Image>,

tools/reaction_analyzer/param/reaction_analyzer.param.yaml

+5-5
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,8 @@
33
use_sim_time: false
44
#running_mode: "perception_planning" # or planning_control
55
run_from_bag: true
6-
path_bag_without_object: /home/berkay/projects/bags/awsim-bag/bag-without-car-full/rosbag2_2024_01_17-16_23_07_0.db3
7-
path_bag_with_object: /home/berkay/projects/bags/awsim-bag/bag-with-car-full/rosbag2_2024_01_17-17_27_14_0.db3
6+
path_bag_without_object: /home/berkay/projects/bags/awsim-bag/bag/lexus_bag_without_car/rosbag2_2024_01_30-13_50_45_0.db3
7+
path_bag_with_object: /home/berkay/projects/bags/awsim-bag/bag/lexus_bag_with_car/rosbag2_2024_01_30-13_50_17_0.db3
88
topic_cloud: /sensing/lidar/top/pointcloud_raw_ex
99
observer:
1010
timer_period: 0.1 # s
@@ -14,9 +14,9 @@
1414
min_jerk_for_brake_cmd: 0.3
1515
test_manager:
1616
entity:
17-
x: 81389.51599364934
18-
y: 49924.1119766238
19-
z: 42.240638732910156
17+
x: 81392.97671487389
18+
y: 49927.361443601316
19+
z: 42.13605499267578
2020
roll: 0.0
2121
pitch: 0.0
2222
yaw: 90.0

tools/reaction_analyzer/src/reaction_analyzer_node.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -1063,7 +1063,6 @@ void ReactionAnalyzerNode::onTimer()
10631063
if (
10641064
initialization_state_ptr &&
10651065
initialization_state_ptr->state == LocalizationInitializationState::INITIALIZED) {
1066-
10671066
if (route_state_ptr && route_state_ptr->state != RouteState::SET && !is_route_set_) {
10681067
// publish goal pose
10691068
is_route_set_ = true;

0 commit comments

Comments
 (0)