struct mola::BridgeROS2::Params
Overview
struct Params { // fields std::string base_link_frame = "base_link"; std::string base_footprint_frame; mrpt::math::TPose3D base_footprint_to_base_link_tf = {0, 0, 0, 0, 0, 0}; std::string odom_frame = "odom"; std::string reference_frame = "map"; bool forward_ros_tf_as_mola_odometry_observations = false; bool publish_odometry_msgs_from_slam = true; bool publish_tf_from_robot_pose_observations = true; bool publish_in_sim_time = false; 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; };
Fields
std::string base_link_frame = "base_link"
tf frame name with respect to sensor poses are measured:
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”
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"
tf frame name for odometry’s frame of reference:
std::string reference_frame = "map"
tf frame name for odometry’s frame of reference:
bool publish_in_sim_time = false
If true, the original dataset timestamps will be used to publish. Otherwise, the wallclock time will be used.