Struct BridgeROS2::Params
Defined in File BridgeROS2.h
Nested Relationships
This struct is a nested type of Class BridgeROS2.
Struct Documentation
-
struct Params
Public Members
-
std::string base_link_frame = "base_link"
tf frame name with respect to sensor poses are measured, and also used for publishing SLAM/localization results (read below).
-
std::string base_footprint_frame
If not empty, the node will broadcast a static /tf from base_footprint to base_link with the TF base_footprint_to_base_link_tf at start up. Normally: “base_footprint”
-
mrpt::math::TPose3D base_footprint_to_base_link_tf = {0, 0, 0, 0, 0, 0}
YAML format: “[x y z yaw pitch roll]” (meters & degrees)
-
std::string odom_frame = "odom"
Used for: (a) importing odometry to MOLA if
forward_ros_tf_as_mola_odometry_observations=true(b) querying${odom_frame} => ${base_link_frame}whenpublish_localization_following_rep105=true.
-
std::string reference_frame = "map"
tf frame used for: (a) See
publish_tf_from_robot_pose_observations(b) To follow REP105 (publish_localization_following_rep105), this must match the frame used as reference in the LocalizationSource (e.g. mola_lidar_odometry)
-
bool publish_localization_following_rep105 = true
How to publish localization to /tf:
false(direct mode): reference_frame (“map”) -> base_link (“base_link”) Note that reference_frame in this case comes from the localization source module (e.g. mola_lidar_odometry), it is not configured here.true(indirect mode), following ROS REP 105:map -> odom(such as “map -> odom -> base_link” = “map -> base_link”)
-
bool forward_ros_tf_as_mola_odometry_observations = false
If enabled, during spinOnce(), the tf
${odom_frame} => ${base_link_frame}will be queried and forwarded as anCObservationOdometryreading to the MOLA subsystem:
-
bool publish_odometry_msgs_from_slam = true
If enabled, SLAM/Localization results will be published as nav_msgs/Odometry messages.
-
std::string publish_odometry_msgs_from_slam_source
-
bool publish_tf_from_slam = true
If enabled, SLAM/Localization results will be published as tf messages, for frames according to explained above for
publish_localization_following_rep105.
-
std::string publish_tf_from_slam_source
-
bool publish_geo_referenced_poses_from_slam = true
If enabled, SLAM/Localization results in geo-referenced maps will be published as geographic_msgs/GeoPoseStamped messages.
-
bool publish_tf_from_robot_pose_observations = true
If enabled, robot pose observations (typically, ground truth from datasets), will be forwarded to ROS as /tf messages:
${reference_frame} => ${base_link}
-
std::string relocalize_from_topic = "/initialpose"
Default in RViz.
-
bool publish_in_sim_time = false
If true, the original dataset timestamps will be used to publish. Otherwise, the wallclock time will be used.
-
double transform_tolerance = 0.1
Future-dating offset [s] applied to the broadcast stamp of the REP-105 localization /tf (
map -> odom). The stamp is set torosNode->now() + transform_tolerance, allowing downstream consumers tolookupTransform(map, base_link, now())without tf2ExtrapolationExceptions. Ignored in direct-publish mode (map -> base_link), where the TF is stamped at the scan acquisition time so consumers can correlate the pose with the sensor data that produced it (andpublish_in_sim_timeis honored).
-
double transform_publish_period = 0.05
Period [s] at which the latest computed REP-105 localization /tf (
map -> odom) is re-broadcast on a wall timer, independent of localization update rate. This keeps the TF buffer always populated for downstream consumers even when the localizer runs slower than the consumer query rate. Set to0to disable the rebroadcast loop (the TF is then only published when a new localization update arrives). Only effective in REP-105 mode: in direct-publish mode (map -> base_link) the rebroadcast is skipped to avoid re-stamping a stale pose as “current” when the localizer stalls — in that mode there is noodom -> base_linkedge carrying real motion, so the robot would silently appear frozen-but-fresh.
-
double period_publish_new_map = 5.0
-
double period_publish_static_tfs = 1.0
-
double period_publish_diagnostics = 1.0
-
double period_check_new_mola_subs = 1.0
-
int wait_for_tf_timeout_milliseconds = 100
-
std::string georef_map_reference_frame = "map"
-
std::string georef_map_utm_frame = "utm"
-
std::string georef_map_enu_frame = "enu"
-
bool odometry_as_robot_pose_observation = true
If true (default), subscribed nav_msgs/Odometry messages are converted to mrpt::obs::CObservationRobotPose (full SE(3) pose + 6x6 covariance), suitable for multi-source fusion in the state estimation smoother. If false, they are converted to mrpt::obs::CObservationOdometry (2D pose, no covariance), which is more appropriate for 2D SLAM/mapping pipelines.
-
std::string base_link_frame = "base_link"