neo_kinematics_omnidrive2¶
Summary¶
The neo_kinematics_omnidrive package provides a means to translate platform control values into individual motor commands, as well as computing the platform’s odometry from its motor encoders.
It is intended to be used for mobile platforms with omni-directional drives, such as the MPO-700.
This package contains 2 nodes that communicates with each other through ROS messages.
Location: https://github.com/neobotix/neo_kinematics_omnidrive2
neo_omnidrive_node¶
- The responsiblity of this node is as follows:
- to convert the cartesian velocity commands into joint velocity commands
- to estimate the robot’s odometry based upon the joint states received from the omnidrive modules
- to publish the odom data as ROS message for determining the position of the robot, joint trajectory message for the motor controllers to perform the desired motion and broadcasts the necessary tf frames
Publishes:
- /tf (tf2_msgs/msg/TFMessage)
- Populates the topic with the transformation of base frame with respect to odom
- /odom (nav_msgs/msg/odometery)
- The odometry topic that publishes the robot’s state information, including position, orientation, and velocity. This topic is typically used for localization and navigation purposes, allowing other nodes to understand the robot’s movement within its environment.
- /joint_trajectory (trajectory_msg/msg/joint_trajectory)
- The joint trajectory topic that publishes commands for the robot’s joints to follow a specified trajectory. This topic is used to control the movements of the robot’s joints by providing a series of waypoints that define the desired positions, velocities over time.
- Estimated based on the cartesian velocity commands
- neo_omnidrive_socketcan_node subscribes for this message
Subscribes:
- /cmd_vel (geometry_msgs/msg/TwistStamped)
- The velocity command topic that subscribes velocity commands for the robot from the neo_teleop2 node.
- This topic includes linear and angular velocities that control the robot’s movement in the x, y directions and as well as the rotation.
- /joint_states (sensor_msgs/msg/JointState)
- The joint states topic that subscribes the state information of the robot’s joints from the neo_omnidrive_socketcan_node.
- This topic contains data such as the position, velocity, and effort of each joint.
- /joy (sensor_msgs/msg/Joy)
- Subscribes to this topic to listen for homing request from the users.
- The request is mapped to a key on the joystick keypad and the same can be changed in the configs.
Services:
- /kinematics_omnidrive/lock_platform (neo_srvs2/srvs/LockPlatform)
- stop platform from moving
- /kinematics_omnidrive/unlock_platform (neo_srvs2/srvs/UnlockPlatform)
- allow platform to move again
- /kinematics_omnidrive/reset_omni_wheels (neo_srvs2/srvs/ResetOmniWheels)
- resets the wheels to given steering angles in rad (by default set to 0)
neo_omnidrive_socketcan_node¶
- The responsiblity of this node is as follows:
- The node is responsible to set and to read the joint commands and joint states to and from motor controllers respectively. The joint commands are received from the neo_omnidrive_node
- The read joint states are published as ROS messages. Both the encoder position and as well as the joint angles with respect to the drives home position.
- This node is responsible to perform the homing process of the omnidrive modules
Publishes:
- /joint_states (sensor_msgs/msg/JointState)
- The joint states topic that publishes the state information of the robot’s joints (in joint angles)
- /joint_states_raw (sensor_msgs/msg/JointState)
- The joint states topic that publishes the raw state information of the robot’s joints (in encoder increaments)
Subscribes:
- /joint_trajectory (trajectory_msg/msg/joint_trajectory)
- The joint trajectory topic that subscribes commands for the robot’s joints to follow a specified trajectory. This topic is used to control the movements of the robot’s joints by providing a series of waypoints that define the desired positions, velocities, and accelerations over time.
- The information is translated and sent to the motor controllers
- /emergency_stop_state (neo_msgs2/msg/EmergencyStopState)
- This topic activates the motors and monitors the status of the motors when the EMStop is disabled.
- /joy (sensor_msgs/msg/Joy)
- Subscribes to this topic to listen for homing request from the users.
- The request is mapped to a key on the joystick keypad and the same can be changed in the configs.