Only released in EOL distros:
Package Summary
The main ric_robot robot package
- Maintainer: RoboTiCan <support AT robotican DOT net>
- Author: RoboTiCan <support AT robotican DOT net>
- License: BSD
- Source: git https://github.com/robotican/ric.git (branch: hydro-devel)
Package Summary
The main ric_robot robot package
- Maintainer status: maintained
- Maintainer: RoboTiCan <support AT robotican DOT net>
- Author: RoboTiCan <support AT robotican DOT net>
- License: BSD
- Source: git https://github.com/robotican/ric.git (branch: indigo-devel)
Contents
Overview
The ric_robot package is the main package which allows to communicate and control the different robots which is made by RoboTiCan.
Usage
Launching the robot
Users can run the main robot launch file (e.g. lizi.launch or komodo.launch) to initiate all the robot controllers and sensors with a single command.
$ roslaunch ric_robot komodo.launch id:=<ID>
For example, running the launch file with komodo id value of 1:
$ roslaunch ric_robot komodo.launch id:=1
This command should be executed on the robot computer. For remote operation see the ric_base_station package. The id number sets the robot name to be komodo_<ID>, this is extremely important when working with several robots as a group of robots. This allows giving each robot in the group a unique name. The id argument can be any desired id number. The id number affect the namespace and the robot description file links and joint names. All the topics, services and parameters will have a komodo_<ID> prefix. The robot launch file is also used to load nodes for the webcams, the Asus RGB-D camera, the Hokuyo laser scanner and the robot arm launch file (komodo_arm.launch).
The robot launch file also loads the configuration file (e.g. ric_robot/config/default_komodo.yaml) which contains various parameters .
Controlling the arm
To control the Komodo robot arm see the Controlling the Komodo arm tutorial.
Using the Laser scanner
See hokuyo_node for package details.
Relevant lines in the launch file:
1 <node pkg="hokuyo_node" type="hokuyo_node" name="hokuyo_node" output="screen">
2 <param name="port" value="/dev/Hokuyo" />
3 <param name="frame_id" value="komodo_$(arg id)_Laser_link" />
4 </node>
The readings are published on the /komodo_<ID>/scan topic.
Using the depth sensor (ASUS Xtion PRO LIVE)
See openni2_launch for package details.
Relevant lines in the launch file:
1 <include file="$(find openni2_launch)/launch/openni2.launch">
2 <arg name="camera" value="komodo_$(arg id)_Asus_Camera" />
3 </include>
Using the cameras
See usb_cam for package details.
Relevant lines in the launch file (for each camera):
1 <node pkg="usb_cam" type="usb_cam_node" name="arm_cam_node" output="screen" respawn="true">
2 <param name="~video_device" value="/dev/video0" />
3 <param name="~camera_frame_id" value="komodo_$(arg id)_Arm_Camera_link" />
4 <param name="~pixel_format" value="yuyv" />
5 <param name="~image_width" value="320" />
6 <param name="~image_height" value="240" />
7 </node>
Reading the ultrasonic range finders
The Komodo and Lizi robots have three ultrasonic range finders (URF) mounted on the sides and on the back of the robot. The range readings are published under the following topics:
/komodo_<ID>/Rangers/Left_URF
/komodo_<ID>/Rangers/Rear_URF
/komodo_<ID>/Rangers/Right_URF
Nodes
ric_node
This is the main robot node.Subscribed Topics
cmd_vel (geometry_msgs/Twist)- The robot listens to this topic and set its forward and angular velocity accordingly.
Published Topics
gps_pub (sensor_msgs/NavSatFix)- This topic publishes the GPS location of the robot.
- This topic publishes the orientation of the robot as measured by the internal IMU (Inertial Measurement Unit).
- This topic publishes the location and orientation of the robot based on the odometry computation of the wheels rotations.
- Left Ultrasonic Range Finder readings
- Rear Ultrasonic Range Finder readings
- Right Ultrasonic Range Finder readings
Services
set_odom (ric_robot/set_odom)- This service set the odometry of the robot to any desired location and orientation, it should receive three fields: float32 x, float32 y, float32 theta.
Parameters
fuse_imu_roll_pitch (boolean, default: false)- This parameter when true uses the IMU's roll and pitch measurements. If false it assumes the robot is on a horizontal surface.
- This parameter when true uses the IMU's yaw measurement instead of the calculated odometry heading. If false uses the robot odometry to determine its heading.
- Robot wheels diameter im meters.
- Robot width in meters.
- Wheels encoders cpr = (ppr*4)
serial_node
This is an internal node that is responsible for the communication between the internal micro-controller and the computer. This node belongs to the rosserial_python package(http://wiki.ros.org/rosserial).Subscribed Topics
command (ric_robot/ric_command)- Instead of using the cmd_vel topic, one may want to directly command the robot motors. The ric_robot/ric_command message contains two fields: int32 left_wheel, int32 right_wheel . The values are in encoder ticks per second units.
- This topic sends command to the Lizi robot pan tilt system that orients the RGB-D sensor. The ric_pan_tilt message contains two fields: float32 pan_angle and float32 tilt_angle. The values are in radians units. Note that the positive directions of the pan-tilt are left and up respectively. A single message is enough to set the required angles (no need for publishing these messages continuously). The pan angle range of motion is -35 to +35, and the tilt range is -30 to +30. These limitations are constrained by software.
Published Topics
ric_status (ric_robot/ric_status)- This topic publishes the rover and sensors modules batteries voltages in Volts and the faults report. The faults parameter is constructed from 4 bits as follows: Bit 0 is set if the RC remote control is on and the robot is on manual control mode. Bit 1 is set if the communication with the motors driver is fault. Bit 2 is set if GPS location is not valid. Bit 3 is set if IMU readings are not valid. faults = (Bit 0)*1 + (Bit 1)*2 + (Bit 2)*4 + (Bit 3)*8. Note that the minimum voltage for the komodo sensors\arm battery is around 11.5V and for the rover battery it is around 23V.
- Internal use topic.
- Internal use topic.
Services
reset_encoders (std_srv/Empty)- This service reset the encoder readings on the micro-controller counters.
- This service allows calibrating the IMU accelerometers and magnetometer and the Remote control. see the Calibrating the robot IMU and Calibrating the robot RC tutorials.
- This service restart the micro-controller.
- This service allows to set the relays module outputs (only if you have a relay on your robot). e.g. some komodo robots have a front light connected to channel 1.
Parameters
pid_constants (float array, default: [0.02,0.2,0.0,0.5,1.0] for lizi, [0.02,0.08, 0.0, 0.05,1.0] for komodo)- [kp, ki, kd, alpha(for velocity low-pass filter), control_dt (control loop interval in milliseconds)]
komodo_arm
This node have two main functions. The first function is to read the arm actuators states and publish them as a sensor_msgs/JointState message. The second function is to control the arm elevator.Subscribed Topics
elevator_controller/pos_command (ric_robot/ric_elevator_command)- This topic listen to position commands for the arm elevator. Commanding the elevator is possible only after a successful homing procedure.
Published Topics
joint_states (sensor_msgs/JointState)- This topic publish the arm joints states as sensor_msgs/JointState message.
Services
elevator_controller/set_position (ric_robot/set_elevator)- This service allows to set (override) the elevator position.
- This service initiate the elevator homing procedure.
Report a Bug
Use GitHub to report bugs or submit feature requests. [View active issues]