Skip to content

Commit

Permalink
Adding catkinized baxter_msgs to baxter_common.
Browse files Browse the repository at this point in the history
  • Loading branch information
rethink-kmaroney committed Aug 14, 2013
1 parent e45e5c5 commit abcb832
Show file tree
Hide file tree
Showing 39 changed files with 333 additions and 3 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@ baxter_common
RSDK Wiki: http://github.com/RethinkRobotics/sdk-docs/wiki

## Repository Description
URDF and 3D models describing the Baxter Research Robot by Rethink Robotics Inc.
URDF, 3D models, and custom messages describing the Baxter Research Robot from Rethink Robotics Inc.
5 changes: 3 additions & 2 deletions baxter_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
<package>
<name>baxter_common</name>
<version>0.6.1</version>
<description>URDF and meshes describing the Baxter robot from Rethink
Robotics.
<description>URDF, meshes, and custom messages
describing the Baxter robot from Rethink Robotics.
</description>

<maintainer email="[email protected]">
Expand All @@ -22,6 +22,7 @@
<buildtool_depend>catkin</buildtool_depend>

<run_depend>baxter_description</run_depend>
<run_depend>baxter_msgs</run_depend>

<export>
<metapackage/>
Expand Down
51 changes: 51 additions & 0 deletions baxter_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
cmake_minimum_required(VERSION 2.8.3)
project(baxter_msgs)

find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs)

add_message_files(
FILES
AnalogIOState.msg
AnalogIOStates.msg
AnalogOutputCommand.msg
AssemblyState.msg
CalibrateArmEnable.msg
CameraControl.msg
CameraSettings.msg
DigitalIOState.msg
DigitalIOStates.msg
DigitalOutputCommand.msg
EndpointState.msg
GripperCommand.msg
GripperIdentity.msg
GripperProperties.msg
GripperState.msg
HeadPanCommand.msg
HeadState.msg
ITB.msg
ITBStates.msg
JointCommandMode.msg
JointPositions.msg
JointTorques.msg
JointVelocities.msg
RobustControllerStatus.msg
TareData.msg
TareEnable.msg
UpdateSource.msg
UpdateSources.msg
UpdateStatus.msg
)

add_service_files(
FILES
CloseCamera.srv
ListCameras.srv
LSCores.srv
OpenCamera.srv
RMCores.srv
SolvePositionIK.srv
)

generate_messages(DEPENDENCIES geometry_msgs std_msgs)

catkin_package(CATKIN_DEPENDS std_msgs geometry_msgs)
3 changes: 3 additions & 0 deletions baxter_msgs/msg/AnalogIOState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
time timestamp
float64 value
bool isInputOnly
2 changes: 2 additions & 0 deletions baxter_msgs/msg/AnalogIOStates.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string[] names
AnalogIOState[] states
4 changes: 4 additions & 0 deletions baxter_msgs/msg/AnalogOutputCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
##the name of the output
string name
##the value to set output
uint16 value
17 changes: 17 additions & 0 deletions baxter_msgs/msg/AssemblyState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
bool enabled # true if enabled
bool stopped # true if stopped -- e-stop asserted
bool error # true if a component of the assembly has an error
#
# The following are specific to the robot top-level assembly:
uint8 estop_button # One of the following:
uint8 ESTOP_BUTTON_UNPRESSED = 0 # Robot is not stopped and button is not pressed
uint8 ESTOP_BUTTON_PRESSED = 1
uint8 ESTOP_BUTTON_UNKNOWN = 2 # STATE_UNKNOWN when estop was asserted by a non-user source
uint8 ESTOP_BUTTON_RELEASED = 3 # Was pressed, is now known to be released, but robot is still stopped.
#
uint8 estop_source # If stopped is true, the source of the e-stop. One of the following:
uint8 ESTOP_SOURCE_NONE = 0 # e-stop is not asserted
uint8 ESTOP_SOURCE_USER = 1 # e-stop source is user input (the red button)
uint8 ESTOP_SOURCE_UNKNOWN = 2 # e-stop source is unknown
uint8 ESTOP_SOURCE_FAULT = 3 # MotorController asserted e-stop in response to a joint fault
uint8 ESTOP_SOURCE_BRAIN = 4 # MotorController asserted e-stop in response to a lapse of the brain heartbeat
10 changes: 10 additions & 0 deletions baxter_msgs/msg/CalibrateArmEnable.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
## @file CalibrateArmEnable.msg See the file below for additional documentation
## @addtogroup RobustControllersMsgs
## @{
## @class RobustControllersMsgs::CalibrateArmEnable

bool isEnabled
string uid
std_msgs/Empty data

## @}
13 changes: 13 additions & 0 deletions baxter_msgs/msg/CameraControl.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
int32 id
int32 value

int32 CAMERA_CONTROL_EXPOSURE=100
int32 CAMERA_CONTROL_GAIN=101
int32 CAMERA_CONTROL_WHITE_BALANCE_R=102
int32 CAMERA_CONTROL_WHITE_BALANCE_G=103
int32 CAMERA_CONTROL_WHITE_BALANCE_B=104
int32 CAMERA_CONTROL_WINDOW_X=105
int32 CAMERA_CONTROL_WINDOW_Y=106
int32 CAMERA_CONTROL_FLIP=107
int32 CAMERA_CONTROL_MIRROR=108
int32 CAMERA_CONTROL_RESOLUTION_HALF=109
4 changes: 4 additions & 0 deletions baxter_msgs/msg/CameraSettings.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
int32 width
int32 height
float32 fps
CameraControl[] controls
7 changes: 7 additions & 0 deletions baxter_msgs/msg/DigitalIOState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
int8 state
bool isInputOnly

int8 OFF = 0
int8 ON = 1
int8 PRESSED = 1
int8 UNPRESSED = 0
2 changes: 2 additions & 0 deletions baxter_msgs/msg/DigitalIOStates.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string[] names
DigitalIOState[] states
4 changes: 4 additions & 0 deletions baxter_msgs/msg/DigitalOutputCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
##the name of the output
string name
##the value to set output
bool value
3 changes: 3 additions & 0 deletions baxter_msgs/msg/EndpointState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
geometry_msgs/Pose pose
geometry_msgs/Twist twist
geometry_msgs/Wrench wrench
6 changes: 6 additions & 0 deletions baxter_msgs/msg/GripperCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
## General electric gripper command message
float32 position # position, as a percentage of max position; 0=closed - 100=open
float32 force # force limit, as a percentage of max force; 0=none - 100=max
float32 velocity # velocity, as a percentage of max velocity; 0=none - 100=max
float32 holding # holding force, as a percentage of max velocity; 0=none - 100=max
float32 deadZone # dead zone, as a percentage of max position; 0=none - 100=max
14 changes: 14 additions & 0 deletions baxter_msgs/msg/GripperIdentity.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
string name # Gripper type name
uint8 type # Gripper type identifier
# Heartland gripper type enumeration:
uint8 NO_GRIPPER = 0
uint8 SUCTION_CUP_GRIPPER = 1
uint8 PNEUMATIC_GRIPPER = 2
uint8 ELECTRIC_GRIPPER = 128
#
uint8 hardware_id # Gripper hardware id
# Gripper hardware id enumeration:
uint8 INVALID_GRIPPER_HARDWARE_ID = 0
uint8 version_major # Gripper version, 0 if none
uint8 version_minor # Gripper version, 0 if none
uint8 revision_lsb # Gripper revision number, 0 if none
6 changes: 6 additions & 0 deletions baxter_msgs/msg/GripperProperties.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Gripper properties
#
bool hasForce # true if the gripper has force control
bool hasPosition # true if the gripper has position control
bool isReverse # true if the gripper grips when opened

39 changes: 39 additions & 0 deletions baxter_msgs/msg/GripperState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# The following Gripper State fields are tristate: 0 = false; 1 = true; 2 = unknown/unsupported
uint8 STATE_FALSE = 0
uint8 STATE_TRUE = 1
uint8 STATE_UNKNOWN = 2
#
uint8 enabled # true if enabled
uint8 calibrated # true if calibration has completed
uint8 ready # true if ready to grip
uint8 moving # true if moving
uint8 gripping # true if gripping
uint8 missed # true if GRIP/GOTO/SET was commanded and the gripper reaches the end of travel
uint8 error # true if the gripper is in an error state
#
uint8 command # current gripper command, one of the following:
# Note that while these have the same as values as the gripper opcodes they
# are not used that way.
uint8 CMD_IDLE = 0
uint8 CMD_GET_ID = 1
uint8 CMD_RESET_ALL = 2
uint8 CMD_RESET_FSM = 3
uint8 CMD_CALIBRATE = 4
uint8 CMD_PREPARE_TO_GRIP = 5
uint8 CMD_GRIP = 6
uint8 CMD_RELEASE = 7
uint8 CMD_GOTO = 8
uint8 CMD_STOP = 9
uint8 CMD_SET = 10
uint8 CMD_CLEAR_CALIBRATION = 11
#
float32 position # position as a percentage of the max position; 0=closed - 100=open
#
float32 POSITION_CLOSED = 0.0
float32 POSITION_OPEN = 100.0
#
float32 force # force as a percentage of max force; 0=none - 100=max
#
float32 FORCE_MIN = 0.0
float32 FORCE_MAX = 100.0
#
4 changes: 4 additions & 0 deletions baxter_msgs/msg/HeadPanCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
#Header header
float32 target # radians for target, 0 str
int32 speed # between 0 and 100, 100 = max

3 changes: 3 additions & 0 deletions baxter_msgs/msg/HeadState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
float32 pan
bool isPanning
bool isNodding
13 changes: 13 additions & 0 deletions baxter_msgs/msg/ITB.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
bool[4] buttons
bool up
bool down
bool left
bool right
uint8 wheel


# true if the inner light is on, false if not
bool innerLight

# true if the outer light is on, false if not
bool outerLight
3 changes: 3 additions & 0 deletions baxter_msgs/msg/ITBStates.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# used when publishing multiple itbs
string[] names
ITB[] states
4 changes: 4 additions & 0 deletions baxter_msgs/msg/JointCommandMode.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
uint8 POSITION=1
uint8 VELOCITY=2
uint8 TORQUE=3
uint8 mode
4 changes: 4 additions & 0 deletions baxter_msgs/msg/JointPositions.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Joint angles in radians:
float64[] angles
# A list of names associated with the above angles
string[] names
4 changes: 4 additions & 0 deletions baxter_msgs/msg/JointTorques.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Joint torques in Nm:
float64[] torques
# A list of names associated with the above torques
string[] names
4 changes: 4 additions & 0 deletions baxter_msgs/msg/JointVelocities.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Joint velocities in radians/sec:
float64[] velocities
# A list of names associated with the above velocities
string[] names
23 changes: 23 additions & 0 deletions baxter_msgs/msg/RobustControllerStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# True if the RC is enabled and running, false if not.
bool isEnabled

# The state of the RC with respect to its completion goal. One of
# NOT_COMPLETE, COMPLETE_W_FAILURE, or COMPLETE_W_SUCCESS
int32 complete
int32 NOT_COMPLETE = 0
int32 COMPLETE_W_FAILURE = 1
int32 COMPLETE_W_SUCCESS = 2

# Identifies the sender of the Enable message that the RC is using for its
# commands. This should correspond to the "uid" field of a recently published
# RC *Enable message.
string controlUid

# Set to true when the RC self-disables as a result of too much time elapsing
# without receiving an Enable message.
bool timedOut

# A list of relevant error codes. Error codes are defined by the individual
# robust controllers, consult a robust controller's documentation to see what
# error codes it generates.
string[] errorCodes
1 change: 1 addition & 0 deletions baxter_msgs/msg/TareData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
bool tuneGravitySpring
3 changes: 3 additions & 0 deletions baxter_msgs/msg/TareEnable.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
bool isEnabled
string uid
baxter_msgs/TareData data
4 changes: 4 additions & 0 deletions baxter_msgs/msg/UpdateSource.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string devname
string filename
string version
string uuid
2 changes: 2 additions & 0 deletions baxter_msgs/msg/UpdateSources.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string uuid
UpdateSource[] sources
20 changes: 20 additions & 0 deletions baxter_msgs/msg/UpdateStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# See the class UpdateRunner()
# status: One-word description of the current action being performed
# long_description: Details pertaining to status if any. Used for verbose error messages.

uint16 status
float32 progress
string long_description

uint16 STS_IDLE = 0
uint16 STS_INVALID = 1
uint16 STS_BUSY = 2
uint16 STS_CANCELLED = 3
uint16 STS_ERR = 4
uint16 STS_MOUNT_UPDATE = 5
uint16 STS_VERIFY_UPDATE = 6
uint16 STS_PREP_STAGING = 7
uint16 STS_MOUNT_STAGING = 8
uint16 STS_EXTRACT_UPDATE = 9
uint16 STS_LOAD_KEXEC = 10

33 changes: 33 additions & 0 deletions baxter_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version="1.0"?>
<package>
<name>baxter_msgs</name>
<version>0.6.1</version>
<description>
Messages and Services required for communication
with the Baxter robot from Rethink Robotics.
</description>

<maintainer email="[email protected]">
Rethink Robotics Inc.
</maintainer>
<license>BSD</license>
<url type="website">http://www.rethinkrobotics.com</url>
<url type="repository">
https://github.com/RethinkRobotics/sdk-examples
</url>
<url type="bugtracker">
https://github.com/RethinkRobotics/sdk-examples/issues
</url>
<author>Rethink Robotics Inc.</author>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>

<run_depend>message_runtime</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>geometry_msgs</run_depend>

</package>
3 changes: 3 additions & 0 deletions baxter_msgs/srv/CloseCamera.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
string name
---
int32 err
2 changes: 2 additions & 0 deletions baxter_msgs/srv/LSCores.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
---
string[] cores
2 changes: 2 additions & 0 deletions baxter_msgs/srv/ListCameras.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
---
string[] cameras
4 changes: 4 additions & 0 deletions baxter_msgs/srv/OpenCamera.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string name
CameraSettings settings
---
int32 err
4 changes: 4 additions & 0 deletions baxter_msgs/srv/RMCores.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string core
---
int32 err
string err_str
4 changes: 4 additions & 0 deletions baxter_msgs/srv/SolvePositionIK.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
geometry_msgs/PoseStamped[] pose_stamp
---
baxter_msgs/JointPositions[] joints
bool[] isValid

0 comments on commit abcb832

Please sign in to comment.