Only released in EOL distros:
Package Summary
Sawyer Roch robot driver
- Maintainer status: developed
- Maintainer: Carl <wzhang AT softrobtech DOT com>
- Author: Mike Purvis <mpurvis AT clearpathrobotics DOT com>, Paul Bovbel <pbovbel AT clearpathrobotics DOT com>, Carl <wzhang AT softrobtech DOT com>
- License: BSD
- Bug / feature tracker: https://github.com/SawYer-Robotics/roch_robot/issues
- Source: git https://github.com/SawYer-Robotics/roch_robot.git (branch: indigo)
Package Summary
Sawyer Roch robot driver
- Maintainer status: maintained
- Maintainer: Chen <gchen AT softrobtech DOT com>
- Author: Mike Purvis <mpurvis AT clearpathrobotics DOT com>, Paul Bovbel <pbovbel AT clearpathrobotics DOT com>, Chen <gchen AT softrobtech DOT com>
- License: BSD
- Bug / feature tracker: https://github.com/SawYer-Robotics/roch_robot/issues
- Source: git https://github.com/SawYer-Robotics/roch_robot.git (branch: kinetic)
See Robots/Roch get more installation or tutorials and information, roch_base based on ros_control.
And also refrence husky_base.
Overview
The roch_base package has some demos for testing whether normal for data of sensors, such as ultrasonic, psd, cliff etc. And also has a demo of launch files, you can checkout what in. roch_node is core node for roch_base package. And all hardware interface is configured by roch_control package.
roch_node
Drivers and communication with ROS and Roch MCU node. Contains ros_control integration via diff_drive_controller, imu_sensor_controller and joint_state_controller.Subscribed Topics
roch_velocity_controller/cmd_vel (geometry_msgs/Twist)- Twist velocity command for Roch, muxed in roch_control. External clients should publish to bare cmd_vel topic.
Published Topics
roch_velocity_controller/odom (nav_msgs/Odometry)- Odometry information from Roch MCU.
- Status information from Roch MCU and roch_node. Also exposed over standard diagnostics interface.
- Debug data for raw Imu sensor, Just for Debugging.
- Imu data processed, used by roch_node.
- Raw command for communication with Roch MCU, for Debugging.
- Cliff sensor data for Roch and used by roch_node, roch_sensorpc and roch_safety_controller.
- PSD sensor data for Roch and used by roch_node, roch_sensorpc and roch_safety_controller.
- Ultrasonic sensor data for Roch and used by roch_node, roch_sensorpc and roch_safety_controller.
- All sensor' state of Roch, used by roch_node and roch_sensorpc.
Parameters
~control_frequency (double, default: 10.0)- Frequency at which Roch MCU is controlled for velocity and polled for odometry information.
- Frequency at which Roch is polled for diagnostic and status information.
- Diameter for Roch wheel, in meters.
- Max accelerated velocity for Roch.
- Max speed for Roch.
- Command timeout for Roch communication with MCU, in Hz.
- How tall is safety for Roch with cliff sensor can publish, in meters.
- How tall is safety for Roch with psd sensor can publish, in meters.
- Communication port with Roch on PC.
- Imu frame link for Roch description used for sending imu data.
Demos
There are have about 5 demos you can run for testing:
- test_encoder
- test_imu
- test_platformInfo
- test_rangefinder
- test_speed
And they have common steps for using:
At first, make sure you had finished under:
- 1.Roch has power on.
- 2.USB cable Roch and your computer.
3.Make sure you has run roscore.
rosrun roch_base test_<name_you_want>
Report a Bug
Use github to report bugs or request features.