Struct BridgeROS2::Params

Nested Relationships

This struct is a nested type of Class BridgeROS2.

Struct Documentation

struct Params

Public Members

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_link to base_footprint with the TF base_footprint_to_base_link_tf at start up. Normally: “base_footprint”

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} when publish_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_lida_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 an CObservationOdometry reading to the MOLA subsystem:

bool publish_odometry_msgs_from_slam = true

If enabled, SLAM/Localization results will be published as nav_msgs/Odometry messages.

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.

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 period_publish_new_localization = 0.2
double period_publish_new_map = 5.0
double period_publish_static_tfs = 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"