Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
motion_computation::conversion::impl Namespace Reference

Functions

std::pair< carma_perception_msgs::msg::PredictedState, double > composePredictedState (const tf2::Vector3 &curr_pt, const tf2::Vector3 &prev_pt, const rclcpp::Time &prev_time_stamp, const rclcpp::Time &curr_time_stamp, double prev_yaw)
 Composes a PredictedState message form a provided current point and previous point. It calculates the speed from these points using mobility_path_time_step. More...
 
void calculateAngVelocityOfPredictedStates (carma_perception_msgs::msg::ExternalObject &object)
 Helper function to fill in the angular velocity of the external object. More...
 
double getYawFromQuaternionMsg (const geometry_msgs::msg::Quaternion &quaternion)
 Gets the yaw angle in degrees described by the provided quaternion. More...
 
tf2::Vector3 transform_to_map_frame (const tf2::Vector3 &ecef_point, const lanelet::projection::LocalFrameProjector &map_projector)
 Transforms ecef point to map frame using internally saved map transform. More...
 
std::vector< geometry_msgs::msg::Pose > sample_2d_path_from_radius (const geometry_msgs::msg::Pose &pose, double velocity, double radius_of_curvature, double period, double step_size)
 
std::vector< geometry_msgs::msg::Pose > sample_2d_linear_motion (const geometry_msgs::msg::Pose &pose, double velocity, double period, double step_size)
 
geometry_msgs::msg::PoseWithCovariance pose_from_gnss (const lanelet::projection::LocalFrameProjector &projector, const tf2::Quaternion &ned_in_map_rotation, const lanelet::GPSPoint &gps_point, const double &heading, const double lat_variance, const double lon_variance, const double heading_variance)
 
std::vector< carma_perception_msgs::msg::PredictedState > predicted_poses_to_predicted_state (const std::vector< geometry_msgs::msg::Pose > &poses, double constant_velocity, const rclcpp::Time &start_time, const rclcpp::Duration &step_size, const std::string &frame, double initial_pose_confidence, double initial_vel_confidence)
 
rclcpp::Time get_psm_timestamp (const carma_v2x_msgs::msg::PSM &in_msg, rclcpp::Clock::SharedPtr clock)
 

Function Documentation

◆ calculateAngVelocityOfPredictedStates()

void motion_computation::conversion::impl::calculateAngVelocityOfPredictedStates ( carma_perception_msgs::msg::ExternalObject &  object)

Helper function to fill in the angular velocity of the external object.

Parameters
ExternalObjectto fill in its angular velocities

Definition at line 211 of file mobility_path_to_external_object.cpp.

212{
213 if (!object.dynamic_obj || object.predictions.size() == 0) {
214 return;
215 }
216
217 // Object's current angular velocity
218 double dt = (rclcpp::Time(object.header.stamp) - rclcpp::Time(object.predictions[0].header.stamp))
219 .seconds();
220 object.velocity.twist.angular.z =
221 (impl::getYawFromQuaternionMsg(object.pose.pose.orientation) -
222 impl::getYawFromQuaternionMsg(object.predictions[0].predicted_position.orientation)) /
223 dt;
224
225 // Predictions' angular velocities
226 auto prev_orient = object.pose.pose.orientation;
227 auto prev_time = rclcpp::Time(object.predictions[0].header.stamp);
228 for (auto & pred : object.predictions) {
229 dt = (rclcpp::Time(pred.header.stamp) - prev_time).seconds();
230 pred.predicted_velocity.angular.z =
231 (impl::getYawFromQuaternionMsg(prev_orient) -
232 impl::getYawFromQuaternionMsg(pred.predicted_position.orientation)) /
233 dt;
234 }
235}
double getYawFromQuaternionMsg(const geometry_msgs::msg::Quaternion &quaternion)
Gets the yaw angle in degrees described by the provided quaternion.

References getYawFromQuaternionMsg().

Referenced by motion_computation::conversion::convert().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ composePredictedState()

std::pair< carma_perception_msgs::msg::PredictedState, double > motion_computation::conversion::impl::composePredictedState ( const tf2::Vector3 &  curr_pt,
const tf2::Vector3 &  prev_pt,
const rclcpp::Time &  prev_time_stamp,
const rclcpp::Time &  curr_time_stamp,
double  prev_yaw 
)

Composes a PredictedState message form a provided current point and previous point. It calculates the speed from these points using mobility_path_time_step.

Parameters
curr_ptcurrent point
prev_ptprev_pt. this point is recorded in the state
prev_time_stampprev_pt's time stamp. This time is recorded in the state
curr_time_stampThe timestamp of the second point when used to compute velocity at prev point
prev_yawA previous yaw value in radians to use if the two provided points are equivalent
Returns
std::pair<carma_perception_msgs::msg::PredictedState,double> where the first element is the prediction including linear velocity, last_time, orientation filled in and the second element is the yaw in radians used to compute the orientation

Definition at line 166 of file mobility_path_to_external_object.cpp.

169{
170 carma_perception_msgs::msg::PredictedState output_state;
171 // Set Position
172 output_state.predicted_position.position.x = prev_pt.x();
173 output_state.predicted_position.position.y = prev_pt.y();
174 output_state.predicted_position.position.z = prev_pt.z();
175
176 // Set Orientation
177 Eigen::Vector2d vehicle_vector = {curr_pt.x() - prev_pt.x(), curr_pt.y() - prev_pt.y()};
178 Eigen::Vector2d x_axis = {1, 0};
179 double yaw = 0.0;
180 if (
181 vehicle_vector.norm() <
182 0.000001) { // If there is zero magnitude use previous yaw to avoid divide by 0
183 yaw = prev_yaw;
184 RCLCPP_DEBUG_STREAM(
185 rclcpp::get_logger("motion_computation::conversion"),
186 "Two identical points sent for predicting heading. Forced to use previous yaw or 0 if "
187 "first "
188 "point");
189 } else {
190 yaw = std::acos(vehicle_vector.dot(x_axis) / (vehicle_vector.norm() * x_axis.norm()));
191 }
192
193 tf2::Quaternion vehicle_orientation;
194 vehicle_orientation.setRPY(0, 0, yaw);
195 output_state.predicted_position.orientation.x = vehicle_orientation.getX();
196 output_state.predicted_position.orientation.y = vehicle_orientation.getY();
197 output_state.predicted_position.orientation.z = vehicle_orientation.getZ();
198 output_state.predicted_position.orientation.w = vehicle_orientation.getW();
199
200 // Set velocity
201 output_state.predicted_velocity.linear.x =
202
203 vehicle_vector.norm() / (curr_time_stamp - prev_time_stamp).seconds();
204
205 // Set timestamp
206 output_state.header.stamp = builtin_interfaces::msg::Time(prev_time_stamp);
207
208 return std::make_pair(output_state, yaw);
209}

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function:

◆ get_psm_timestamp()

rclcpp::Time motion_computation::conversion::impl::get_psm_timestamp ( const carma_v2x_msgs::msg::PSM &  in_msg,
rclcpp::Clock::SharedPtr  clock 
)

Definition at line 476 of file psm_to_external_object_convertor.cpp.

478{
479 boost::posix_time::ptime utc_time_of_current_psm;
480
481 // Get the utc epoch start time
482 static const boost::posix_time::ptime inception_boost(
483 boost::posix_time::time_from_string("1970-01-01 00:00:00.000"));
484
485 // Determine if the utc time of the path history can be used instead of the
486 // sec_mark The sec_mark is susceptible to large error on minute transitions
487 // due to missing "minute of the year" field If the second mark in the path
488 // history is identical and the full utc time is provided with ms resolution
489 // then it can be assumed the initial_position is the same as the PSM data and
490 // the utc_time can be used instead of sec_mark
491 // clang-format off
492
493 const auto initial_position_time{in_msg.path_history.initial_position.utc_time};
494 if ((in_msg.presence_vector &
495 carma_v2x_msgs::msg::PSM::HAS_PATH_HISTORY) &&
496 (in_msg.path_history.presence_vector &
497 carma_v2x_msgs::msg::PathHistory::HAS_INITIAL_POSITION) &&
498 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::YEAR) &&
499 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::MONTH) &&
500 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::DAY) &&
501 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::HOUR) &&
502 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::MINUTE) &&
503 (initial_position_time.presence_vector & j2735_v2x_msgs::msg::DDateTime::SECOND) &&
504 (in_msg.sec_mark.millisecond == initial_position_time.second.millisecond)) {
505 // clang-format on
506 RCLCPP_DEBUG_STREAM(
507 rclcpp::get_logger("motion_computation::conversion"),
508 "Using UTC time of path history to determine PSM "
509 "timestamp. Assumed valid since UTC is fully specified "
510 "and sec_mark == utc_time.seconds in this message.");
511
512 boost::posix_time::time_duration time_of_day =
513 boost::posix_time::hours(in_msg.path_history.initial_position.utc_time.hour.hour) +
514 boost::posix_time::minutes(in_msg.path_history.initial_position.utc_time.minute.minute) +
515 boost::posix_time::milliseconds(
516 in_msg.path_history.initial_position.utc_time.second.millisecond);
517
518 boost::gregorian::date utc_day(
519 in_msg.path_history.initial_position.utc_time.year.year,
520 in_msg.path_history.initial_position.utc_time.month.month,
521 in_msg.path_history.initial_position.utc_time.day.day);
522
523 utc_time_of_current_psm = boost::posix_time::ptime(utc_day) + time_of_day;
524 } else { // If the utc time of the path history cannot be used to account for minute
525 // change over, then we have to default to the sec mark
526
527 RCLCPP_WARN_STREAM_THROTTLE(
528 rclcpp::get_logger("motion_computation::conversion"), *clock.get(),
529 rclcpp::Duration(5, 0).nanoseconds(),
530 "PSM PathHistory utc timstamp does not match "
531 "sec_mark. Unable to determine the minute of "
532 "the year used for PSM data. Assuming local "
533 "clock is exactly synced. This is NOT "
534 "ADVISED.");
535
536 // Get the current ROS time
537 auto current_time = clock->now();
538
539 // Convert the ros time to a boost duration
540 boost::posix_time::time_duration duration_since_inception(
541 lanelet::time::durationFromSec(current_time.seconds()));
542
543 // Get the current ROS time in UTC
544 auto curr_time_boost = inception_boost + duration_since_inception;
545
546 // Get duration of current day
547 auto duration_in_day_till_current_time = curr_time_boost.time_of_day();
548
549 // Extract hours and minutes
550 auto hour_count_in_day = duration_in_day_till_current_time.hours();
551 auto minute_count_in_hour = duration_in_day_till_current_time.minutes();
552
553 // Get the duration of the minute in the day
554 auto start_of_minute_in_day = boost::posix_time::hours(hour_count_in_day) +
555 boost::posix_time::minutes(minute_count_in_hour);
556
557 // Get the start of the day in ROS time
558 boost::posix_time::ptime start_of_day(curr_time_boost.date());
559
560 // Ge the start of the current minute in ROS time
561 boost::posix_time::ptime utc_start_of_current_minute = start_of_day + start_of_minute_in_day;
562
563 // Compute the UTC PSM stamp from the sec_mark using ROS time as the clock
564
565 boost::posix_time::time_duration s_in_cur_minute =
566 boost::posix_time::milliseconds(in_msg.sec_mark.millisecond);
567
568 utc_time_of_current_psm = utc_start_of_current_minute + s_in_cur_minute;
569 }
570
571 boost::posix_time::time_duration nsec_since_epoch = utc_time_of_current_psm - inception_boost;
572
573 if (nsec_since_epoch.is_special()) {
574 RCLCPP_ERROR_STREAM(
575 rclcpp::get_logger("motion_computation::conversion"),
576 "Computed psm nsec_since_epoch is special (computation "
577 "failed). Value effectively undefined.");
578 }
579
580 return rclcpp::Time(nsec_since_epoch.total_nanoseconds());
581}

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function:

◆ getYawFromQuaternionMsg()

double motion_computation::conversion::impl::getYawFromQuaternionMsg ( const geometry_msgs::msg::Quaternion &  quaternion)

Gets the yaw angle in degrees described by the provided quaternion.

Parameters
quaternionThe quaternion to extract yaw from
Returns
The yaw in degrees

Definition at line 237 of file mobility_path_to_external_object.cpp.

238{
239 tf2::Quaternion orientation;
240 orientation.setX(quaternion.x);
241 orientation.setY(quaternion.y);
242 orientation.setZ(quaternion.z);
243 orientation.setW(quaternion.w);
244
245 double roll;
246 double pitch;
247 double yaw;
248 tf2::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
249
250 return yaw;
251}

Referenced by calculateAngVelocityOfPredictedStates().

Here is the caller graph for this function:

◆ pose_from_gnss()

geometry_msgs::msg::PoseWithCovariance motion_computation::conversion::impl::pose_from_gnss ( const lanelet::projection::LocalFrameProjector &  projector,
const tf2::Quaternion &  ned_in_map_rotation,
const lanelet::GPSPoint &  gps_point,
const double &  heading,
const double  lat_variance,
const double  lon_variance,
const double  heading_variance 
)

Convert the position information into the map frame using the proj library

Convert the position information into the map frame using the proj library

Definition at line 339 of file psm_to_external_object_convertor.cpp.

344{
347 lanelet::BasicPoint3d map_point = projector.forward(gps_point);
348
349 RCLCPP_DEBUG_STREAM(
350 rclcpp::get_logger("motion_computation::conversion"),
351 "map_point: " << map_point.x() << ", " << map_point.y() << ", " << map_point.z());
352
353 if (
354 fabs(map_point.x()) > 10000.0 ||
355 fabs(map_point.y()) > 10000.0) { // Above 10km from map origin earth curvature will start to
356 // have a negative impact on system performance
357
358 RCLCPP_WARN_STREAM(
359 rclcpp::get_logger("motion_computation::conversion"),
360 "Distance from map origin is larger than supported by system "
361 "assumptions. Strongly advise "
362 "alternative map origin be used. ");
363 }
364
366 // This logic assumes that the orientation difference between an NED frame
367 // located at the map origin and an NED frame located at the GNSS point are
368 // sufficiently small that they can be ignored. Therefore it is assumed the
369 // heading report of the GNSS system regardless of its postion in the map
370 // without change in its orientation will give the same result (as far as we
371 // are concered).
372
373 tf2::Quaternion R_m_n(ned_in_map_rotation); // Rotation of NED frame in map
374 // frame
375 tf2::Quaternion R_n_h; // Rotation of sensor heading report in NED frame
376 R_n_h.setRPY(0, 0, heading * wgs84_utils::DEG2RAD);
377
378 tf2::Quaternion R_m_s = R_m_n * R_n_h; // Rotation of sensor in map frame under assumption that
379 // distance from map origin is sufficiently small so as to
380 // ignore local changes in NED orientation
381
382 RCLCPP_DEBUG_STREAM(
383 rclcpp::get_logger("motion_computation::conversion"),
384 "R_m_n (x,y,z,w) : ( " << R_m_n.x() << ", " << R_m_n.y() << ", " << R_m_n.z() << ", "
385 << R_m_n.w());
386
387 RCLCPP_DEBUG_STREAM(
388 rclcpp::get_logger("motion_computation::conversion"),
389 "R_n_h (x,y,z,w) : ( " << R_n_h.x() << ", " << R_n_h.y() << ", " << R_n_h.z() << ", "
390 << R_n_h.w());
391
392 RCLCPP_DEBUG_STREAM(
393 rclcpp::get_logger("motion_computation::conversion"),
394 "R_m_s (x,y,z,w) : ( " << R_m_s.x() << ", " << R_m_s.y() << ", " << R_m_s.z() << ", "
395 << R_m_s.w());
396
397 tf2::Transform T_m_s(
398 R_m_s, tf2::Vector3(
399 map_point.x(), map_point.y(),
400 map_point.z())); // Reported position and orientation
401 // of sensor frame in map frame
402
403 tf2::Transform T_m_n_no_heading(
404 R_m_n, tf2::Vector3(0, 0, 0)); // Used to transform the covariance
405
406 // This covariance represents the covariance of the NED frame N-lat,
407 // E-lon, heading- angle east of north This means that the covariance is
408 // in the NED frame, and needs to be transformed to the map frame
409 // clang-format off
410 std::array<double, 36> input_covariance = {
411 lat_variance, 0, 0, 0, 0, 0,
412 0, lon_variance, 0, 0, 0, 0,
413 0, 0, 1, 0, 0, 0,
414 0, 0, 0, 1, 0, 0,
415 0, 0, 0, 0, 1, 0,
416 0, 0, 0, 0, 0, heading_variance
417 };
418 // clang-format on
419
420 std::array<double, 36> new_cov = tf2::transformCovariance(
421 input_covariance,
422 // Per the usage of transformCovariance in tf2_geometry_msgs
423 // this frame should be the transform between the map which the pose
424 // is in an the target frame.
425 T_m_n_no_heading);
426
427 // Populate message
428 geometry_msgs::msg::PoseWithCovariance pose;
429 pose.pose.position.x = T_m_s.getOrigin().getX();
430 pose.pose.position.y = T_m_s.getOrigin().getY();
431 pose.pose.position.z = T_m_s.getOrigin().getZ();
432
433 pose.pose.orientation.x = T_m_s.getRotation().getX();
434 pose.pose.orientation.y = T_m_s.getRotation().getY();
435 pose.pose.orientation.z = T_m_s.getRotation().getZ();
436 pose.pose.orientation.w = T_m_s.getRotation().getW();
437
438 pose.covariance = new_cov;
439
440 return pose;
441}
geometry_msgs::msg::PoseWithCovariance::_covariance_type transformCovariance(const geometry_msgs::msg::PoseWithCovariance::_covariance_type &cov_in, const tf2::Transform &transform)
Transform the covariance matrix of a PoseWithCovariance message to a new frame.

References covariance_helper::transformCovariance().

Referenced by motion_computation::conversion::convert().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ predicted_poses_to_predicted_state()

std::vector< carma_perception_msgs::msg::PredictedState > motion_computation::conversion::impl::predicted_poses_to_predicted_state ( const std::vector< geometry_msgs::msg::Pose > &  poses,
double  constant_velocity,
const rclcpp::Time &  start_time,
const rclcpp::Duration &  step_size,
const std::string &  frame,
double  initial_pose_confidence,
double  initial_vel_confidence 
)

Definition at line 443 of file psm_to_external_object_convertor.cpp.

447{
448 std::vector<carma_perception_msgs::msg::PredictedState> output;
449 output.reserve(poses.size());
450
451 rclcpp::Time time(start_time);
452
453 for (auto p : poses) {
454 time += step_size;
455 carma_perception_msgs::msg::PredictedState pred_state;
456 pred_state.header.stamp = time;
457 pred_state.header.frame_id = frame;
458
459 pred_state.predicted_position = p;
460 pred_state.predicted_position_confidence =
461 0.9 * initial_pose_confidence; // Reduce confidence by 10 % per timestep
462 initial_pose_confidence = pred_state.predicted_position_confidence;
463
464 pred_state.predicted_velocity.linear.x = constant_velocity;
465 pred_state.predicted_velocity_confidence =
466 0.9 * initial_vel_confidence; // Reduce confidence by
467 // 10 % per timestep
468 initial_vel_confidence = pred_state.predicted_velocity_confidence;
469
470 output.push_back(pred_state);
471 }
472
473 return output;
474}

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function:

◆ sample_2d_linear_motion()

std::vector< geometry_msgs::msg::Pose > motion_computation::conversion::impl::sample_2d_linear_motion ( const geometry_msgs::msg::Pose &  pose,
double  velocity,
double  period,
double  step_size 
)

Definition at line 293 of file psm_to_external_object_convertor.cpp.

295{
296 std::vector<geometry_msgs::msg::Pose> output;
297 output.reserve((period / step_size) + 1);
298
299 tf2::Vector3 pose_in_map_translation(pose.position.x, pose.position.y, pose.position.z);
300 tf2::Quaternion pose_in_map_quat(
301 pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
302
303 tf2::Transform pose_in_map(pose_in_map_quat, pose_in_map_translation);
304
305 double total_dt = 0;
306
307 while (total_dt < period) {
308 // Compute the 2d position and orientation in the Pose frame
309 total_dt += step_size;
310 double dx_from_start = velocity * total_dt; // Assuming linear motion in pose frame
311
312 double x = pose.position.x + dx_from_start;
313
314 tf2::Vector3 position(x, 0, 0);
315
316 // Convert the position and orientation in the pose frame to the map frame
317 tf2::Transform pose_to_sample(tf2::Quaternion::getIdentity(), position);
318 tf2::Transform map_to_sample = pose_in_map * pose_to_sample;
319
320 geometry_msgs::msg::Pose sample_pose;
321
322 sample_pose.position.x = map_to_sample.getOrigin().x();
323 sample_pose.position.y = map_to_sample.getOrigin().y();
324 sample_pose.position.z = map_to_sample.getOrigin().z();
325
326 sample_pose.orientation.x = map_to_sample.getRotation().x();
327 sample_pose.orientation.y = map_to_sample.getRotation().y();
328 sample_pose.orientation.z = map_to_sample.getRotation().z();
329 sample_pose.orientation.w = map_to_sample.getRotation().w();
330
331 output.emplace_back(sample_pose);
332 }
333
334 return output;
335}

References process_traj_logs::x.

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function:

◆ sample_2d_path_from_radius()

std::vector< geometry_msgs::msg::Pose > motion_computation::conversion::impl::sample_2d_path_from_radius ( const geometry_msgs::msg::Pose &  pose,
double  velocity,
double  radius_of_curvature,
double  period,
double  step_size 
)

Definition at line 236 of file psm_to_external_object_convertor.cpp.

239{
240 std::vector<geometry_msgs::msg::Pose> output;
241 output.reserve((period / step_size) + 1);
242
243 tf2::Vector3 pose_in_map_translation(pose.position.x, pose.position.y, pose.position.z);
244 tf2::Quaternion pose_in_map_quat(
245 pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
246 tf2::Transform pose_in_map(pose_in_map_quat, pose_in_map_translation);
247
248 // The radius of curvature originates from the frame of the provided pose
249 // So the turning center is at (0, r)
250 double center_x_in_pose = 0;
251 double center_y_in_pose = radius_of_curvature;
252
253 double total_dt = 0;
254
255 while (total_dt < period) {
256 // Compute the 2d position and orientation in the Pose frame
257 total_dt += step_size;
258 double delta_arc_length = velocity * total_dt; // Assumes perfect point motion along curve
259
260 double turning_angle = delta_arc_length / radius_of_curvature;
261 double dx_from_center = radius_of_curvature * sin(turning_angle);
262 double dy_from_center = radius_of_curvature * cos(turning_angle);
263
264 double x = center_x_in_pose + dx_from_center;
265 double y = center_y_in_pose + dy_from_center;
266
267 tf2::Vector3 position(x, y, 0);
268
269 tf2::Quaternion quat;
270 quat.setRPY(0, 0, turning_angle);
271
272 // Convert the position and orientation in the pose frame to the map frame
273 tf2::Transform pose_to_sample(quat, position);
274 tf2::Transform map_to_sample = pose_in_map * pose_to_sample;
275
276 geometry_msgs::msg::Pose sample_pose;
277
278 sample_pose.position.x = map_to_sample.getOrigin().x();
279 sample_pose.position.y = map_to_sample.getOrigin().y();
280 sample_pose.position.z = pose.orientation.z; // Reuse the z position from the initial pose
281
282 sample_pose.orientation.x = map_to_sample.getRotation().x();
283 sample_pose.orientation.y = map_to_sample.getRotation().y();
284 sample_pose.orientation.z = map_to_sample.getRotation().z();
285 sample_pose.orientation.w = map_to_sample.getRotation().w();
286
287 output.emplace_back(sample_pose);
288 }
289
290 return output;
291}

References process_traj_logs::x, and process_traj_logs::y.

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function:

◆ transform_to_map_frame()

tf2::Vector3 motion_computation::conversion::impl::transform_to_map_frame ( const tf2::Vector3 &  ecef_point,
const lanelet::projection::LocalFrameProjector &  map_projector 
)

Transforms ecef point to map frame using internally saved map transform.

Parameters
ecef_pointecef_point to transform
map_projectorProjector used for frame conversion
Returns
point in map

Definition at line 253 of file mobility_path_to_external_object.cpp.

255{
256 lanelet::BasicPoint3d map_point = map_projector.projectECEF(
257 {ecef_point.x(), ecef_point.y(), ecef_point.z()},
258 -1); // Input should already be converted to m
259
260 return tf2::Vector3(map_point.x(), map_point.y(), map_point.z());
261}

Referenced by motion_computation::conversion::convert().

Here is the caller graph for this function: