rox_argo_kinematics

This node translates the command velocties from cartesian space to the joint space and sends it to the motors through the relayboardV3 node. The kinematics node, inturn subscribes to the joint states from the relayboard in order to calculate, updates and publishes odometry.

Location: https://github.com/neobotix/rox_argo_kinematics/

Parameters

control_rate:
Type Default
double 50.0
Description

Frequency at which motor commands are sent. (Hz)

wheel_radius:
Type Default
double 0.50
Description

Radius of the wheel. (m)

cmd_timeout:
Type Default
double 0.1
Description

Maximum interval between 2 consecutive velocity commands. (s)

zero_vel_threshold:
 
Type Default
double 0.001
Description

Velocity below which the steering for a wheel is disabled. [m/s]

broadcast_tf:
Type Default
bool true
Description

Broadcasts Transformation frame between the base_link and odom.

small_vel_threshold:
 
Type Default
double 0.02
Description

Velocity below which it is allowed to move a wheel into the outward position. [m/s]

num_wheels:
Type Default
int 4
Description

number of drive modules (need at least 2).

wheel[i].center_pos_x:
 
Type Default
double 1.0
Description

X position of the steering axis. [m]

wheel[i].center_pos_y:
 
Type Default
double 1.0
Description

Y position of the steering axis. [m]

wheel[i].drive_joint_name:
 
Type Default
std::string “rand”
Description

ROS joint name for this motor.

wheel[i].steer_joint_name:
 
Type Default
std::string “rand”
Description

ROS joint name for this motor.

Published Topics

  • odom(nav_msgs/Odometry): Gives the position of the robot in the cartesian space.
  • tf: Publishes the required transforms that maps odom and the base_footprint.
  • drives/joint_trajectory(trajectory_msgs/JointTrajectory): Publishes the joint commands that is later subscribed and converted to motor commands by the argo_drive_node.

Subscribed Topics

  • cmd_vel(geometry_msgs/Twist): Subscribes to the cartesian velocity commands(m/s) published by Teleop, nav2_controller and so on.

Example

/**:
  ros__parameters:
    num_wheels: 3
    control_rate: 50.0
    wheel_radius: 0.050
    wheel_lever_arm: 0.0
    zero_vel_threshold: 0.005
    small_vel_threshold: 0.02
    broadcast_tf: true
    cmd_timeout: 0.2
    trajectory_timeout: 0.1

    wheel0:
      drive_joint_name: "wheel_front_left_joint"
      steer_joint_name: "caster_front_left_joint"
      center_pos_x: 0.265
      center_pos_y: 0.215

    wheel1:
      drive_joint_name: "wheel_back_left_joint"
      steer_joint_name: "caster_back_left_joint"
      center_pos_x: -0.265
      center_pos_y: 0.215

    wheel3:
      drive_joint_name: "wheel_back_right_joint"
      steer_joint_name: "caster_back_right_joint"
      center_pos_x: -0.265
      center_pos_y: -0.215

    wheel2:
      drive_joint_name: "wheel_front_right_joint"
      steer_joint_name: "caster_front_right_joint"
      center_pos_x: 0.265
      center_pos_y: -0.215