APIs

Overall ROS Architecture

rqt_graph

 

Pose Estimation APIs

Here are some caveats for the IMU:

  • the yaw of the IMU pose measurement will drift over time;
  • the x-, y- and z-axis of the IMU frame points the right, the front and the top, respectively;
  • the distance unit is m (meter) and the angle unit is rad (radian) for the IMU measurements.

 

IMU Pose Measurement

Read the IMU sensor pose measurement data, which include orientation, angular velocity, linear acceleration along with their covariance matrices.

  • ROS Topic:
    • IMU sensor pose measurement data for AutoKrawler 1: /ak1/imu/data
    • IMU sensor pose measurement data for AutoKrawler 2: /ak2/imu/data
  • Message Structure (sensor_msgs/Imu):
    • header (std_msgs/Header):
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): the frame of the IMU link (ak[?]_imu_link)
    • orientation (geometry_msgs/Quaternion): the mean orientation of the IMU link
      • x (float64): quarternion x component
      • y (float64): quarternion y component
      • z (float64): quarternion z component
      • w (float64): quarternion w component
    • orientation_covariance (float64[9]): the covariance matrix of the orientation in Euler angle format
    • angular_velocity (geometry_msgs/Vector3): the mean angular velocity of the IMU link
      • x (float64): the angular velocity about the x-axis
      • y (float64): the angular velocity about the y-axis
      • z (float64): the angular velocity about the z-axis
    • angular_velocity_covariance (float64[9]): the covariance matrix of the angular velocity.
    • linear_acceleration (geometry_msgs/Vector3): the mean linear acceleration of the IMU link
      • x (float64): the linear acceleration along the x-axis
      • y (float64): the linear acceleration along the y-axis
      • z (float64): the linear acceleration along the z-axis
    • linear_acceleration_covariance (float64[9]): the covariance matrix of the linear acceleration

 

IMU RPY Measurement

Read the IMU orientation measurement represented by roll, pitch and yaw.

  • ROS Topic:
    • IMU RPY measurement for AutoKrawler 1: /ak1/imu/rpy
    • IMU RPY measurement for AutoKrawler 2: /ak2/imu/rpy
  • Message Structure (geometry_msgs/Vector3Stamped):
    • header (std_msgs/Header):
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): the frame of the IMU link (ak[?]_imu_link)
    • vector (geometry_msgs/Vector3): the magnetic field measurement by the IMU
      • x (float64): the roll of the IMU link
      • y (float64):the pitch of the IMU link
      • z (float64):the yaw of the IMU link, and note that this component will drift over time

 

IMU Magnetic Field Measurement

Read the IMU magnetic field measurement. Notice that this information is not used in odometry state estimation, because the IMU is inside the AutoKrawler and surrounded by a metal shell and wires, so the magnetic field measurement does not accurately reflect the magnetic field of the Earth. Furthermore, it is not reasonable to assume that other planets have the same magnetic fields as the Earth.

  • ROS Topic:
    • IMU magnetic field measurement for AutoKrawler 1: /ak1/imu/mag
    • IMU magnetic field measurement for AutoKrawler 2: /ak2/imu/mag
  • Message Structure (geometry_msgs/Vector3Stamped):
    • header (std_msgs/Header):
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): the frame of the IMU link (ak[?]_imu_link)
    • vector (geometry_msgs/Vector3): the magnetic field measurement by the IMU
      • x (float64): the magnetic force sensed along the x-axis
      • y (float64): the magnetic force sensed along the y-axis
      • z (float64): the magnetic force sensed along the z-axis

Wheel Encoders

Read the wheel encoders sensor data.

  • ROS Topic:
    • Wheel encoders sensor data for AutoKrawler 1: /ak1/joint_states
    • Wheel encoders sensor data for AutoKrawler 2: /ak2/joint_states
  • Message Structure (sensor_msgs/JointState):
    •  header (std_msgs/Header): the header of the message
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): reserved
    • name (string[]): the names of the joints ([‘front_drive’, ‘rear_drive’, ‘front_steer’, ‘rear_steer’])
    • position (float64[]): the encoder positions corresponding of the joints indicated by their names
    • velocity (float64[]): the encoder velocities corresponding of the joints indicated by their names
    • effort (float64[]): reserved

 

Wheel Odometry

Read the wheel odometry data, which comes from the fusion of the sensor data of the joint encoders.

  • ROS Topic:
    • Wheel odometry for AutoKrawler 1: /ak1/odom
    • Wheel odometry for AutoKrawler 2: /ak2/odom
  • Message Structure (nav_msgs/Odometry):
    • header (std_msgs/Header): the header of the message
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): the base frame (ak[n]_odom)
      • child_frame_id (string): the odometry frame with respect to the base frame  (ak[n]_base_link)
    • pose (geometry_msgs/PoseWithCovariance): the pose of the AutoKrawler defined by its mean and covariance matrix
      • pose (geometry_msgs/Pose): the mean of the pose
        • position (geometry_msgs/Point): the mean position of the AutoKrawler
          • x (float64): the mean x-axis coordinate of the AutoKrawler
          • y (float64): the mean y-axis coordinate of the AutoKrawler
          • z (float64): reserved
        • orientation (geometry_msgs/Quaternion): the mean orientation of the AutoKrawler
          • x (float64): reserved
          • y (float64): reserved
          • z (float64): coupled with w part
          • w (float64): coupled with z part
      • covariance (float64[36]): the covariance matrix for the pose (*unknown: why the dimension does not match the pose dimension)
    • twist (geometry_msgs/TwistWithCovariance): the twist (pose velocity) of the AutoKrawler defined by its mean and covariance matrix
      • twist (geometry_msgs/Twist): the mean of the velocity
        • linear (geometry_msgs/Vector3): the mean linear velocity
          • x (float64): the mean linear velocity component along the x-axis of the AutoKrawler
          • y (float64): the mean linear velocity component along the y-axis of the AutoKrawler
          • z (float64): reserved
        • angular (geometry_msgs/Vector3): the mean angular velocity
          • x (float64): reserved
          • y (float64): reserved
          • z (float64): the mean angular velocity of the AutoKrawler on the floor
      • covariance (float64[36]): the covariance matrix of the velocity

Sensor Fusion for Odometry

Read the sensor fusion data for odometry, whose source sesnsor data come from the IMU sensor, the GPS module, and the wheel odometry module.

  • Configuration File:
    • Odometry sensor fusion configuration file for AutoKrawler 1: ~/catkin_ws/src/autokrawler/params/ekf_template_ak1.yaml
    • Odometry sensor fusion configuration file for AutoKrawler 2: ~/catkin_ws/src/autokrawler/params/ekf_template_ak2.yaml
  • ROS Topic:
    • Odometry sensor fusion for AutoKrawler 1: /ak1/odometry/filtered
    • Odometry sensor fusion for AutoKrawler 2: /ak2/odometry/filtered
  • Message Structure (nav_msgs/Odometry):
    • header (std_msgs/Header): the header of the message
      • seq (uint32): the sequence of the message
      • stamp (ROS::Time): the time stamp of the message
      • frame_id (string): the base frame (ak[n]_odom)
      • child_frame_id (string): the odometry frame with respect to the base frame  (ak[n]_base_link)
    • pose (geometry_msgs/PoseWithCovariance): the pose of the AutoKrawler defined by its mean and covariance matrix
      • pose (geometry_msgs/Pose): the mean of the pose
        • position (geometry_msgs/Point): the mean position of the AutoKrawler
          • x (float64): the mean x-axis coordinate of the AutoKrawler
          • y (float64): the mean y-axis coordinate of the AutoKrawler
          • z (float64): reserved
        • orientation (geometry_msgs/Quaternion): the mean orientation of the AutoKrawler
          • x (float64): reserved
          • y (float64): reserved
          • z (float64): coupled with w part
          • w (float64): coupled with z part
      • covariance (float64[36]): the covariance matrix for the pose (*unknown: why the dimension does not match the pose dimension)
    • twist (geometry_msgs/TwistWithCovariance): the twist (pose velocity) of the AutoKrawler defined by its mean and covariance matrix
      • twist (geometry_msgs/Twist): the mean of the velocity
        • linear (geometry_msgs/Vector3): the mean linear velocity
          • x (float64): the mean linear velocity component along the x-axis of the AutoKrawler
          • y (float64): the mean linear velocity component along the y-axis of the AutoKrawler
          • z (float64): reserved
        • angular (geometry_msgs/Vector3): the mean angular velocity
          • x (float64): reserved
          • y (float64): reserved
          • z (float64): the mean angular velocity of the AutoKrawler on the floor
      • covariance (float64[36]): the covariance matrix of the velocity

 

Joystick APIs and Protocols

General Joystick Messages

Publish joystick message for different models of joysticks.

  • ROS Topic:
    • Joystick for AutoKrawler 1: /ak1/joy
    • Joystick for AutoKrawler 2: /ak2/joy
  • Message Structure (sensor_msgs/Joy):
    • header (std_msgs/Header): header of the message
      • seq (uint32): message sequence number
      • stamp (time): message time stamp
      • frame_id (string): reserved
    • axes (float32[]): analog values of different axes of the joystick, in [-1.0, 1.0]
    • buttons (int32[]): boolean values with each indicating if a button is pressed or not, in {0, 1} ~ {released, pressed}

 

Dualshock4 Joystick Protocol

  • Axes:
    • [0] left joy left-right: [-1.0, 1.0] ~ [right, left] ~ [roll right, roll left]
    • [1] left joy up-down: [-1.0, 1.0] ~ [down, up] ~ [backward, forward]
    • [2] right joy left-right: [-1.0, 1.0] ~ [right, left] ~ [yaw clockwise, yaw counter-clockwise]
    • [3] L2 analog button: [-1.0, 1.0] ~ [pressed, released] ~ reserved
    • [4] R2 analog button: [-1.0, 1.0] ~ [pressed, released] ~ reserved
    • [5] right joy up-down: [-1.0, 1.0] ~ [down, up] ~ [descend, ascend]
    • [6] left pad left-right: {-1.0, 0.0, 1.0} ~ {right, released, left} ~ {open claw, stop claw, close claw}
    • [7] left pad up-down: {-1.0, 0.0, 1.0} ~ {down, released, up} ~ {retract winch, stop winch, release winch}
  • Buttons:
    • [0] right pad square/left: {0, 1} ~ {released, pressed} ~ reserved
    • [1] right pad cross/down: {0, 1} ~ {released, pressed} ~ reserved
    • [2] right pad circle/right: {0, 1} ~ {released, pressed} ~ reserved
    • [3] right pad triangle/up: {0, 1} ~ {released, pressed} ~ reserved
    • [4] L1 button: {0, 1} ~ {released, pressed} ~ reserved
    • [5] R1 button: {0, 1} ~ {released, pressed} ~ dead-man switch
    • [6] L2 analog button: {0, 1} ~ {released, pressed} ~ reserved
    • [7] R2 analog button: {0, 1} ~ {released, pressed} ~ reserved
    • [8] SHARE button: {0, 1} ~ {released, pressed} ~ reserved
    • [9] OPTIONS button: {0, 1} ~ {released, pressed} ~ reserved
    • [10] ?: {0, 1} ~ {released, pressed} ~ reserved
    • [11] ?: {0, 1} ~ {released, pressed} ~ reserved
    • [12] Playstation button: {0, 1} ~ {released, pressed} ~ reserved
    • [13] middle pad as a button: {0, 1} ~ {released, pressed} ~ reserved

 

Rover Status Monitoring APIs

IMU Temperature Measurement

Read the IMU temperature measurement for the AutoKrawler core.

  • ROS Topic:
    • IMU temperature measurement for AutoKrawler 1: /ak1/imu/temperature
    • IMU temperature measurement for AutoKrawler 2: /ak2/imu/temperature
  • Message Structure (std_msgs/Float32):
    • data (float32): the temperature of the AutoKrawler core measured by the IMU

 

Battery Voltage

Read the current voltage of the battery.

  • ROS Topic:
    • Battery voltage for AutoKrawler 1: /ak1/diagnostics/battery_voltage
    • Battery voltage for AutoKrawler 2: /ak2/diagnostics/battery_voltage
  • Message Structure (std_msgs/Float32):
    • data (float32): the current voltage of the battery

 

Locomotion APIs

Ackermann Drive

Tell the rover to drive in Ackermann steering mode.

  • ROS Topic:
    • Ackermann drive for AutoKrawler 1: /ak1/cmd_vel
    • Ackermann drive for AutoKrawler 2: /ak2/cmd_vel
  • Message Structure (geometry_msgs/Twist):
    • linear (geometry_msgs/Vector3): velocity control
      • x (float64): the velocity magnitude driving forward, in [-1.0, 1.0] ~ [forward, backward], note that the winch is at the rear of the rover
      • y (float64): reserved
      • z (float64): reserved
    • angular (geometry_msgs/Vector3): steering control
      • x (float64): reserved
      • y (float64): reserved
      • z (float64): the Ackermann steering angle magnitude, in [-0.7, 0.7] ~ [left, right], note that both the front and the rear Ackermann steering servos will actuate

 

Towing Status Monitoring APIs

Towing Winch Status Monitoring

Monitor the towing winch status.

  • ROS Topic:
    • Towing winch status monitoring for AutoKrawler 1: /ak1/towing/winch/status
    • Towing winch status monitoring for AutoKrawler 2: /ak2/towing/winch/status
  • Message Structure (std_msgs/UInt16):
    • data (uint16): can be 1 (“retracted“), 3 (“retracting“), 2 (“released“), 4 (“releasing“) or 0 (“stopped“) which indicates the current status of the towing winch. Note that the status shall be published in a constant frequency all the time.

 

Towing Claw Status Monitoring

Monitor the towing claw status.

  • ROS Topic:
    • Towing claw status monitoring for AutoKrawler 1: /ak1/towing/claw/status
    • Towing claw status monitoring for AutoKrawler 2: /ak2/towing/claw/status
  • Message Structure (std_msgs/UInt16):
    • data (uint16): can be 1 (“closed“), 3 (“closing“), 2 (“open“), 4 (“opening“) or 0 (“stopped“), which indicates the current status of the towing claw. Note that the status shall be published in a constant frequency all the time.

 

Towing Claw Actuator Status Monitoring

Monitor the towing claw actuator status.

  • ROS Topic:
    • Towing claw linear actuator monitoring for AutoKrawler 1: /ak1/towing/claw/actuator
    • Towing claw linear actuator monitoring for AutoKrawler 2: /ak2/towing/claw/actuator
  • Message Structure (std_msgs/UInt16):
    • data (uint16): the claw actuator status, in {0, 1, 2,…, 1023}, where the value indicates the magnitude of the claw linear actuator length.

 

Towing Claw Pressure Monitoring

Monitor the pressure applied to the claw.

  • ROS Topic:
    • Towing claw pressure monitoring for AutoKrawler 1: /ak1/towing/claw/pressure
    • Towing claw pressure monitoring for AutoKrawler 2: /ak2/towing/claw/pressure
  • Message Structure (std_msgs/UInt16):
    • data (uint16): the magnitude of the pressure applied to the claw, in {0, 1, 2,…, 1023}, where the value indicates the magnitude of the pressure.

 

Towing APIs

Towing Winch Control

Control the towing winch.

  • ROS Topic:
    • Towing winch control for AutoKrawler 1: /ak1/towing/winch/control
    • Towing winch control for AutoKrawler 2: /ak2/towing/winch/control
  • Message Structure (std_msgs/UInt16):
    • data (uint16): can be either 1 (“retract“), 2 (“release“) or 0 (“stop“), which indicates the desired status of the towing winch. Note that the control command shall be published in a constant frequency all the time, and any invalid value will be ignored.

 

Towing Claw Control

Control the towing claw.

  • ROS Topic:
    • Towing claw control for AutoKrawler 1: /ak1/towing/claw/control
    • Towing claw control for AutoKrawler 2: /ak2/towing/claw/control
  • Message Structure (std_message/UInt16):
    • data (uint16): can be either 1 (“close“), 2 (“open“) or 0 (“stop“), which indicates the desired status of the towing claw. Note that the control command shall be published in a constant frequency all the time, and any invalid value will be ignored.

 

Winch Control [Discarded]

Control the winch.

  • ROS Topic:
    • Winch control for AutoKrawler 1: /ak1/servo
    • Winch control for AutoKrawler 2: /ak2/servo
  • Message Structure (std_msgs/UInt16):
    • data (uint16): the velocity of the servo, from [1000, 2000]. 1500 is stopped.

 

Towing Arduino Serial (without ros_lib on Arduino)

Serial communication and protocols for the towing Arduino micro-controller.

  • ROS Topic:
    • Towing Arduino serial receiving (from Arduino to ROS) for AutoKrawler 1: /ak1/towing/serial/receive
    • Towing Arduino serial receiving (from Arduino to ROS) for AutoKrawler 2: /ak2/towing/serial/receive
    • Towing Arduino serial sending (from ROS to Arduino) for AutoKrawler 1: /ak1/towing/serial/send
    • Towing Arduino serial sending (from ROS to Arduino) for AutoKrawler 2: /ak1/towing/serial/send
  • Message Structure (std_msgs/String):
    • data (string): the serial message to receive or to send.
  • Protocols:
    • actuation command (to send):
      • format: w[Nwa] c[Nca]
        • [Nwa]: the actuation command for the winch, in {0, 1, 2}, where 0 indicates stopping the current action, 1 indicates retracting the tether, and 2 indicates releasing the tether. Note that the actual actuation should align to the last valid partial command sent, regardless of the current status.
        • [Nca]: the actuation command for (the linear actuator of) the claw, in {0, 12}, where 0 indicates stopping the current action, 1 indicates closing the claw, and 2 indicates opening the claw. Note that the actual actuation should align to the last valid partial command sent, regardless of the current status.
      •  examples:
        • w1 c2“: make the winch tether retracted and the claw open.
        • w0 c1 c1 w0 w1 w1 c4 c12313212 w1 ccc1“: make the winch tether retracted and the claw closed.
    • status feedback command (to receive):
      • format: w[Nws] c[Ncs] l[Nls] f[Nfs]
        • [Nws]: the winch status feedback, in {0, 1, 2, 3, 4}, where 0 indicates the winch is stopped, 1 indicates the winch tether is fully retracted, 2 indicates the winch tether is fully released (to its maximum length), 3 indicates the winch tether is being retracted, and 4 indicates the winch is being released. Note that the last valid partial status feedback received is considered, and the status feedback shall be sent by the Arduino in a constant frequency all the time.
        • [Ncs]: the claw status feedback, in {0, 1, 2, 3, 4}, where 0 indicates the claw is stopped, 1 indicates the claw is fully closed, 2 indicates the claw is fully open, 3 indicates the claw is closing, and 4 indicates the winch is opening. Note that the last valid partial status feedback received is considered, and the status feedback shall be sent by the Arduino in a constant frequency all the time.
        • [Nls]: the claw linear actuator status feedback, in {0, 1, 2,…, 1023}, where the value indicates the magnitude of the claw linear actuator length. Note that the last valid partial status feedback received is considered, and the status feedback shall be sent by the Arduino in a constant frequency all the time.
        • [Nfs]: the force sensor (potentiometer) status feedback, in {0, 2, 3,…, 1023}, where the value indicates the magnitude of the force sensed by the force sensor for the claw. Note that the last valid partial status feedback received is considered, and the status feedback shall be sent by the Arduino in a constant frequency all the time.
      • examples:
        • w1 c3 l156 f198“: the winch tether is fully retracted, the claw is closing, the claw linear actuator length magnitude is 156/1024, and the force sensed for the claw has a magnitude of 198/1024.
        • w1 cccccccc2 l9weqfa f199988888 w1.0 c1 l55 f25 fffff123“: the winch tether is fully retracted, the claw is closed, the claw linear actuator has a length magnitude of 55/1024, and the force sensed for the claw has a magnitude of 25/1024.