Only released in EOL distros:  

Overview

This package contains the hardware interface to control the robot. The rtai_ros_bridge package from rtai_ros_integration stack is used to exchange data with the robot.

Nodes

biped_serializer

Serialization of data that is sent to the BipedRobin controller.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • Desired velocity for WheeledRobin (x, theta)

Published Topics

data_to_rtai (std_msgs/UInt8MultiArray)
  • Serialized data that is sent to the BipedRobin controller via rtai_ros_bridge.

Services

footstep3DInc_srv (biped_robin_msgs/StepTarget3DService)
  • Add one step to the step buffer of BipedRobin (used in walking mode).
movePostureCartesian_srv (biped_robin_msgs/MovePostureCartesianService)
  • Set the desired cartesian posture for BipedRobin (used in cartesian posture mode).
movePostureJoint_srv (biped_robin_msgs/MovePostureJointService)
  • Set the desired joint posture for BipedRobin (used in joint posture mode).
moveGripper_srv (biped_robin_msgs/MoveGripperService)
  • Sets the desired speed/force of the gripper of BipedRobin.
acknowledge_srv (std_srvs/Empty)
  • Send an error acknowledgement to the BipedRobin (e.g. after using the emergency stop button or the stop_srv).
reference_srv (std_srvs/Empty)
  • Used to reference the BipedRobin (just works in service mode).
stop_srv (std_srvs/Empty)
  • Send an stop request to the BipedRobin (before the robot can be moved again the error needs to be acknowledged by acknowledge_srv).
resetState_srv (std_srvs/Empty)
  • Resets the internal state (joint state) of the robot. Can only be called in idle mode)
setMode_srv (biped_robin_msgs/SetModeService)
  • Sets the desired mode of the robot (e.g. 0.. idle mode, 1.. home position mode, 2.. walk position mode, 3.. walk mode, 8.. joint posture mode, 9.. cartesian posture mode).
setParam_srv (biped_robin_msgs/SetParamService)
  • Sets an parameter of BipedRobin to the desired value.

Parameters

par_isRealEnvironment (bool, default: false)
  • Defines if the BipedRobin controller is in a simulated mode or controlls the physical robot.

biped_deserializer

De-serialization of data that was sent by the BipedRobin controller to ROS topics.

Subscribed Topics

data_from_rtai (std_msgs/UInt8MultiArray)
  • Data the BipedRobin Controller sent via rtai_ros_bridge.

Published Topics

joint_states (sensor_msgs/JointState)
  • Joint states of BipedRobin.
bipedRobinGlobalBehaviour (biped_robin_msgs/BipedRobinGlobalBehaviour)
  • Current state and behaviour of BipedRobin
stepsLeftInBuffer (std_msgs/UInt8)
  • Number of steps left in the step buffer of BipedRobin. If the buffer is empty the robot stops walking.

Provided tf Transforms

odombase_link
  • Transfrom from odom to base_link.
base_linkcenter_of_mass
  • Transfrom from base_link to center_of_mass.
base_linkgaze
  • Transfrom from base_link to gaze.
base_linkl_sole
  • Transfrom from base_link to l_sole.
base_linkr_sole
  • Transfrom from base_link to rl_sole.
base_linkbase_footprint
  • Transfrom from base_link to base_footprint.

kinect_transform_publisher.py

Publishes the tranformation from

Subscribed Topics

cur_tilt_angle (std_msgs/Float64)
  • Current angle of the Kinect (e.g. provided by kinect_aux)

Published Topics

tilt_angle (std_msgs/Float64)
  • Desired angle of the Kinect (e.g. used by kinect_aux)

Provided tf Transforms

camera_linkgaze
  • Transfrom from camera_link to the gaze frame (Kinect can be rotated, so this transfrom is not static).

Wiki: biped_robin_driver (last edited 2013-12-02 08:16:20 by JohannesMayr)