Contents
Hardware Requirements
To use this package you need one or more powercubes www.schunk-modular-robotics.com. Alternatively you can use a simulated version without any hardware, see schunk_bringup_sim.
Software Requirements
The installation is tested for Ubuntu 14.04 using ROS indigo. If you discover problems installing them on other platforms, please tell us.
ROS API
The schunk_powercube_chain package provides a configurable node for operating a chain of powercube modules.
schunk_powercube_chain
The schunk_powercube_chain node takes in brics_actuator/JointVelocities messages and sends this directly to the hardware. The chain can be initialized, stopped or recovered via services.Subscribed Topics
joint_group_velocity_controller/command (std_msgs/Float64MultiArray)- Receives velocity commands.
- Receives position commands (Not implemented yet).
Published Topics
/joint_states (sensor_msgs/JointState)- Joint state information for all modules in chain.
- Controller state information for all modules in chain.
- Current operation mode for chain.
- Diagnostics information about chain.
Services
driver/init (std_srvs/Trigger)- Initializes the node and connects to the hardware.
- Stops immediately all hardware movements.
- Recovers the hardware after an emergency stop.
- Sets the operation mode for the node. Currently only "velocity" mode implemented.
Parameters
can_module (string, default: Required)- Can module specifier, e.g. PCAN, ESD
- Device address of can module, e.g. /dev/can0, /dev/pcan2,...
- Baudrate of can module, e.g. 1000, 500,...
- Modul IDs of the powercubes, e.g. [10,11,12,13,...]
- Forces using the M5API moveVel command instead of moveStep.
- List of joint names corresponding to urdf description, e.g. [arm_1_joint, arm_2_joint, arm_3_joint,...]
- List of maximal accelerations for the modules in rad/sec^2, e.g. [0.8,0.8,0.8,...]
- Horizon in seconds for commanding moveStep. E.g. 0.1 commands a step size of 0.1 seconds into the future.
- Controller frequency.
- Minimum duration of publishing joint states if no command is received, otherwise for each received command one joint state message is published.
- Urdf model of the robot, including the joints and links describing the chain of powercubes
Usage/Examples
This package is not intended to be used directly, but with the corresponding launch and yaml files from e.g. schunk_bringup in the schunk_robots stack. For starting only the lwa use
roslaunch schunk_bringup lwa_solo.launch
For including the lwa in your overall launch file use
<include file="$(find schunk_bringup)/components/lwa.launch" />
All hardware configuration is done in the schunk_hardware_config package. A sample parameter file in "schunk_hardware_config/lwa/config/lwa.yaml" could look like this
can_module: PCAN can_device: /dev/pcan1 can_baudrate: 1000 modul_ids: [1,2,3,4,5,6,7] joint_names: [arm_1_joint, arm_2_joint, arm_3_joint, arm_4_joint, arm_5_joint, arm_6_joint, arm_7_joint] max_accelerations: [0.8,0.8,0.8,0.8,0.8,0.8,0.8] frequency: 68 OperationMode: position ptp_vel: 0.4 # rad/sec ptp_acc: 0.1 # rad/sec^2 max_error: 0.2 # rad