This package was created as part of the Marvelmind Indoor GPS integration tutorial for Leo Rover. It provides configuration for navigation for Leo Rover equipped with Marvelmind Starter Set Super-MP-3D.
-
hedge_rcv_bin
Publishes position and rotation data of the mobile beacon mounted to the rover on marvelmind custom message types.hedge_imu_raw(type: marvelmind_nav/hedge_imu_raw)hedge_imu_fusion(type: marvelmind_nav/hedge_imu_fusion)hedge_pos_ang(type: marvelmind_nav/hedge_pos_ang)
Better field description here.
-
wheel_odom_parser
Republishes wheel odometry data published by leo_firmware on message type accepted by robot_localization package.wheel_odom_with_covariance(type: geometry_msgs/TwistWithCovarianceStamped)
wheel_odom(type: geometry_msgs/TwistStamped)
~pub_topic(string) - default:wheel_odom_with_covarianceName of the published topic.~wheel_odom_topic(string) - default:wheel_odomName of the subscribed topic with odometry data from wheels.wheel_odom_covariance_diagonal(double[]) - default:[0.0001, 0.0, 0.0, 0.0, 0.0, 0.001]
Diagonal of the covariance matrix for wheel odometry.
-
imu_parser
Republishes IMU data published byhedge_rcv_binon message types accepted by robot_localization package.parsed_imu(type: sensor_msgs/Imu)
hedge_imu_raw(type: marvelmind_nav/hedge_imu_raw)hedge_imu_fusion(type: marvelmind_nav/hedge_imu_fusion)
~imu_fusion_sub_topic(string) - default:hedge_imu_fusion
Name of the subscribed topic with IMU fusion data from mobile beacon.~imu_raw_sub_topic(string) - default:hedge_imu_raw
Name of the subscribed topic with raw IMU data from mobile beacon.~imu_pub_topic(string) - default:parsed_imu
Name of the published topic.~frame(string) - default:beacon_frame
Frame id in header of publishedsensor_msgs/Imumessage. Defaults to the name of the frame defined in beacon's URDF file.~imu_angular_velocity_covariance_diagonal(double[]) - default:[0.000001, 0.000001, 0.00001]
Diagonal of the covariance matrix for IMU angular velocity.~imu_linear_acceleration_covariance_diagonal(double[]) - default:[0.001, 0.001, 0.001]
Diagonal of the covariance matrix for IMU acceleration.
-
pose_parserRepublishes position data fromhedge_rcv_binnode and odometry data from wheels with covariance as an odometry message.parsed_pose(type: nav_msgs/Odometry)
hedge_pos_ang(type: marvelmind_nav/hedge_pos_ang)wheel_odom_with_covariance(type: geometry_msgs/TwistWithCovarianceStamped)
~pos_sub_topic(string) - default:hedge_pos_ang
Name of the subscribed topic with position data from mobile beacon.~wheel_covariance_topic(string) - default:wheel_odom_with_covariance
Name of the subscribed topic with wheel odometry data with covariance.~pose_pub_topic(string) - default:parsed_pose
Name of the published topic.~frame_id(string) - default:map
Frame id in header of publishednav_msgs/Odometrymessage. Defaults tomap, as topic published by this node is used in ukf node that providesmap->odomtransform.~child_frame(string) - default:beacon_frame
Id of child frame in header of publishednav_msgs/Odometrymessage. Defaults tobeacon_frame, as message published by the topic from this node is position of beacon in the map frame.~pose_covariance_diagonal(double[]) - default:[0.1, 0.1, 0, 0, 0, 0]
Diagonal of the covariance matrix for rover's pose.~min_linear_speed_covariance(double) - default:5.0
Value of the covariance matrix diagonal for rotation about Z axis, when the rover has minimal linear speed (0.2 m/s).~max_linear_speed_covariance(double) - default:1.0
Value of the covariance matrix diagonal for rotation about Z axis, when the rover has maximum linear speed (0.4 m/s).
-
robot_loc_odom
UKF node from robot_localization package which publishesodom->base_footprinttf transform. Uses linear speed in X axis fromwheel_odom_with_covariancetopic and angular speed around Z axis fromparsed_imutopic.odometry/filtered_odom(type: nav_msgs/Odometry)
-
robot_loc_map
UKF node from robot_localization package which publishesmap->odomtf transform. Uses X and Y coordinates and yaw fromparsed_posetopic and linear speed in X axis fromwheel_odom_with_covariancetopic and angular speed around Z axis fromparsed_imutopic.odometry/filtered(type: nav_msgs/Odometry)
marvelmind_localization.launchStarts thehedge_rcv_binfrom ROS_marvelmind_package,imu_parserandpose_parsernodes androbot_loc_odomandrobot_loc_mapnodes from robot_localization.