-
Notifications
You must be signed in to change notification settings - Fork 1
Robot API motion
Anton Deguet edited this page Feb 20, 2018
·
43 revisions
Table of Contents generated with DocToc
We identified the following basic types of motions for collaborative robotics:
Direct access to the low-level controller:
- Use case: User has a smooth trajectory coming from a master arm, recorded trajectory and can send commands at a high rate.
- Space: These commands can be defined either in the cartesian or joint space.
- Type: These commands can be either position, velocity or effort based. Positions can be provided as increments from the latest commanded position.
- Continuity: Users must send continuous commands. The low-level controller is not required to generate intermediate goals to ensure that the command is feasible (i.e. goal must be closed to current state).
- Time: Users are expected to send commands periodically at a rate close to the low-level rate. These commands commands are preemptive.
Simple interpolation:
- Use case: User has a smooth trajectory coming from a master arm, recorded trajectory and but can't send commands at a high rate (e.g. 50Hz visual tracking, remote tele-operation).
- Space: These commands can be defined either in the cartesian or joint space.
- Type: These commands are position based, either absolute or incremental.
- Continuity: Users must send continuous commands. The low-level controller will compute intermediary positions to smooth the motion.
- Time: Users are expected to send commands periodically at a rate lower than the low-level controller. The velocity of the motion is defined by the user commands. These commands commands are preemptive.
Move with trajectory generation:
- Use case: User wants to move to a given position and stop there (e.g. home position, pick and place)
- Space: These commands can be defined either in the cartesian or joint space.
- Type: These commands are position based, either absolute or incremental.
- Continuity: Users must send feasible commands. The low-level controller will compute a complete trajectory to move from the current state (position and velocity) to the desired goal.
- Time: Users are expected to send a single command and wait for completion before sending a new one. Time of execution is defined by the trajectory generation parameters (acceleration and velocity).
Command names are based on the space, type and control level. The prefix identifies the control mode, it is followed by an underscore (_
) and two letters identifying the space and type. For example, servo_cp
is a "servo" command with a cartesian (c
) position (p
) goal.
- Space:
j
(joint),c
(cartesian) - Type:
- Joint:
s
(state: position, velocity and effort) - Cartesian:
p
(pose),v
(twist),i
(incremental pose),f
(wrench)
- Joint:
- Measured:
measured
(physical measure from sensors) - Control level:
servoed
(lastservo
received),commanded
(lastinterp
ormove
received)
- Space:
j
(joint),c
(cartesian) - Type:
p
(position or pose),v
(velocity or twist),i
(incremental position or pose),f
(force, wrench or effort) - Control level:
servo
(low-level),interp
(basic interpolation),move
(full trajectory planning)
- Payload: sensor_msgs/JointState
-
Specification:
-
time Header.stamp
: time of measurement [required] -
string name[]
: array of joint names [required] -
float64 position[]
: array of measured joint positions [required] -
float64 velocity[]
: array of measured joint velocities [optional] -
float64 effort[]
: array of measured joint efforts [optional]
-
-
Notes:
- The low-level controller can set all vectors sizes to zero to indicate an invalid joint state (e.g. robot not yet calibrated or powered).
-
velocity
should be provided if the low-level controller has the ability to perform velocity estimation. -
effort
should be provided if the low-level controller has torque sensors or current feedback per joints. - Size of all non-empty vectors must match.
- Payload: geometry_msgs/TransformStamped
-
Specification:
-
time Header.stamp
: time of measurement, if the measured cartesian position is based on a measured joint position, the time stamp should be the same asmeasured_js
[required] -
string Header.frame_id
: reference frame [required] -
string frame_id
: moving frame [required] -
Transform transform
:translation
androtation
for the measured cartesian position (e.g. forward kinematics based on measured joint position) [required]
-
-
Notes:
- The low-level controller can set the
transform.rotation
quaternion to zero to indicate an invalid cartesian position.
- The low-level controller can set the
- Payload: sensor_msgs/JointState
-
Specification:
-
time Header.stamp
: time associated to lastservo
command. This can be defined by a directservo
command or an intermediary set point calculated byinterp
ormove
. -
string name[]
: array of joint names [required] -
float64 position[]
: array of goal joint positions [required iff the last command was position based] -
float64 velocity[]
: array of goal joint velocities [required iff the last command was velocity based] -
float64 effort[]
: array of goal joint efforts [required iff the last command was effort based]
-
-
Notes:
- All vectors
position
,velocity
andeffort
must be empty except the one corresponding to the lastservo
command. - Size of all non-empty vectors must match.
- All vectors
? should we provide velocity and/or acceleration used for interpolation or trajectory generation ?
? velocity based on interp and/or trajectory generator ?