-
Notifications
You must be signed in to change notification settings - Fork 16
Arm and Wheels Control
This describes the current system, it will likely be rewritten by a new member very soon.
Essentially, the user (through the joystick) moves a virtual point in 2D space, and the motors (in concert with the encoders) move so the end effector moves to this location. The user also sets the angle of the gripper relative to the ground (theta pitch) and manually moves the base motor, and the gripper motors.
The topics are as follows:
- /joy (type sensor_msgs/msg/Joy) - the messages from the joystick
- /absenc_values (type EncoderValues, which has angle_1, angle_2, and angle_3) - the angles reported from each of the 3 encoders
- /joint_states (type sensor_msgs/msg/JointState) - the desired angles of the arm motors. These are in radians, where 0 means the joint is aligned with the previous joint. A positive angle means it is rotated clockwise.
- /arm_values (type Float32MultiArray) - an array of 6 values for motor speeds
The nodes are:
-
arm_controller_node:
- Sends motor speeds over serial to the microcontroller
- Receives joy messages to do forward kinematics with PS4 controller. Also attempts to detect the "type" of the controller. This is because, with the PS4 controller, the mapping from the buttons and axes to the buttons and axes arrays seems to change almost randomly between a couple of possible mappings.
-
absenc_node:
- handles gripper and base motor movement (IE gets from /joy and publishes this to /arm_values)
- receives angles from motor encoders and publishes to /absenc_values
- handles motor movement for IK (receives desired angles (/joint_states) and current angles
from
/dev/ttyUSB0
) and sets motor speeds (publishes to /arm_values) so the motors will move toward the desired angle. Also publishes the current angles toabsenc_values
-
IKNode:
- Publishes desired motor angles for IK
- Subscribes to /absenc_values to initialize its virtual point
-
/absenc_values
: The angles of the encoders in degrees are published fromabsenc_node
in degrees. There are currently (dec 2024) three encoders, on three of the four 12v motors that are on the arm (all of these motors except the bottom one). The angles are relative to the previous joint, where if the joint isn't 'bent' is set at 0 degrees. The encoders are absolute magnetic encoders, meaning that if the rover is turned on and off again will still report the same value. -
/joint_states
: This is the desired motor angles from the IK solver in radians. -
/arm_values
: Desired motor speeds, range is -1 to 1.
The arm moves in a 2D coordinate space, with x and z axes. The x axis is forward and back from the perspective of the rover, and z is vertical. Because we don't have an encoder on the base, we only have 2D control.
The supported controller is the logitech flight stick we have.
- Moving forward and back (x): vertical axis of the joystick
- Moving up and down (z): Trigger and button 2
- Spinning the arm base: spin of the joystick
- The pitch angle (the angle of the gripper with respect to the ground): Horizontal axis of the dpad
- The speed of the vertical movement of the gripper: set by the turnable control that is below the main joystick, it has "-" and "+" labels.
Hold down button #3. Then, moving the joystick forward and back (on the vertical axis) will move the robot forward and back; moving left and right (the horizontal axis) will cause it to turn on the spot.
Currently (pending a rewrite in progress by Tung) the arm_controller_node handles this, it is subscribed to /joy and sends serial messages on /dev/ttyTHS1
(although it used to be /dev/ttyTHS0
).
Motor directions:
- 0: positive is clockwise (as viewed from top)
- 1: positive is counter clockwise (as viewed from rover’s left side)
- 2: positive is counter clockwise (as viewed from rover’s left side)
- 3: positive is counter clockwise (as viewed from rover’s left side) Serial message format:
- 0x4E
- 0x18 (indicates 24 bytes payload)
- 24 bytes representing 4 floating point values in the range from -1024 to 1024
- 0x0A
Messages can be received also on /arm_values. This is a float array, in range from -1 to 1.