Skip to content

LeoRover/leo_marvelmind_tutorial

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

5 Commits
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

leo_marvelmind

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.

Nodes

  • hedge_rcv_bin
    Publishes position and rotation data of the mobile beacon mounted to the rover on marvelmind custom message types.

    Published topics:

    Better field description here.

  • wheel_odom_parser
    Republishes wheel odometry data published by leo_firmware on message type accepted by robot_localization package.

    Published topics:

    Subscribed topics:

    Parameters:

    • ~pub_topic (string) - default: wheel_odom_with_covariance Name of the published topic.
    • ~wheel_odom_topic (string) - default: wheel_odom Name 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 by hedge_rcv_bin on message types accepted by robot_localization package.

    Published topics:

    Subscribed topics:

    Parameters:

    • ~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 published sensor_msgs/Imu message. 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_parser Republishes position data from hedge_rcv_bin node and odometry data from wheels with covariance as an odometry message.

    Published topics:

    Subscribed topics:

    Parameters:

    • ~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 published nav_msgs/Odometry message. Defaults to map, as topic published by this node is used in ukf node that provides map->odom transform.
    • ~child_frame (string) - default: beacon_frame
      Id of child frame in header of published nav_msgs/Odometry message. Defaults to beacon_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 publishes odom->base_footprint tf transform. Uses linear speed in X axis fromwheel_odom_with_covariance topic and angular speed around Z axis from parsed_imu topic.

    Published topics:

  • robot_loc_map
    UKF node from robot_localization package which publishes map->odom tf transform. Uses X and Y coordinates and yaw from parsed_pose topic and linear speed in X axis fromwheel_odom_with_covariance topic and angular speed around Z axis from parsed_imu topic.

    Published topics:

Launch files

Releases

No releases published

Packages

No packages published