Only released in EOL distros:
Package Summary
The forte_rc_robot package
- Maintainer: Ingeniarius, Ltd. <welcome AT ingeniarius DOT pt>
- Author: Ingeniarius, Ltd. <support AT ingeniarius DOT pt>
- License: BSD
- Source: git https://github.com/ingeniarius-ltd/forte_rc_robot.git (branch: indigo-devel)
ForteRC
ForteRC is a mobile robotic platform designed for research in the field of social robotics. ForteRC is a robust omnidirectional platform that can carry more than 100kg - ideal for transporting heavy loads or even a person in indoor facilities.
Processing System
ForteRC comprises a two-layer processing system:
High-level: CPU with WiFi and Bluetooth 4.0, running Ubuntu 14.04.3 LTS and ROS Indigo (Intel NUC NUC5i5RYH)
Low-level: Microcontroller Arduino-based board (Arduino MEGA ADK)
Sensory System
ForteRC is equipped with the following sensors:
16 x ultrasonic sensors (Devantech SRF02)
2 x LRF (Hokuyo UST-/20LX)
1 x ToF camera (Microsoft Kinect One)
Actuation System
ForteRC can act on the environment in different ways:
4 x mecanum wheels (8" Mecanum Wheel Set) controlled by high-power DC motors (CIM Motor) with 12.750 PPR encoders (E4P-250-250-N-S-D-D-B)
1 x 6 DoF robotic manipulator that enables the interaction with the surrounding environment so as to, for instance, deliver a load or open a door (Commonplace Robotics Mover6)
1 x 2 DoF robot head for human-robot interaction with servo controller (Micro Maestro)
Electrical Scheme
ForteRC communication and power schemes, please see:
Packages Overview
Basic Configuration
Component |
ROS package/stack |
Robot model (URDF) |
Control
Component |
ROS package/stack |
Motors Controller |
|
Head Controller |
|
Manipulator Controller |
High-Level Capabilities
Component |
ROS package/stack |
Teleop |
|
Navigation |
Quick start
To benefit from ROS directly within ForteRC's internal CPU (Intel NUC NUC5i5RYH), you must first connect to it. To do so, you can directly work using its touchscreen, or even connecting other peripherals (keyboard, mouse, etc). Yet, the simplest way is to simply use a remote desktop software. ForteRC's internal CPU comes with the NoMachine remote desktop tool, which allows users to directly connect to it using the same software, regardless on their OS.
Follow these steps to work on ForteRC's internal CPU using NoMachine:
Download and install NoMachine on you own computer (NoMachine download page)
- In case ForteRC is already connected to the same wireless network than you, then jump to step 6
Check for available wireless networks and connect to the one with SSID Forte-Ap
Introduce the following password: 1234567890
Connect to ForteRC using NoMachine, under the IP 10.42.0.1, using nuc as both username and password, then jump to step 7
If you are connected to the same network than ForteRC, you will be able to see it through NoMachine, and you just have to connect to it, using nuc as both username and password
- That's it - Enjoy!
Forte_RC Description
FORTE_ROSv10 provides urdf models for Forte_RC robot.
ForteRC 3D model in rviz.
Launch
roslaunch FORTE_ROSv10 display.launch
Navigation
Please check ForteRC_navigation.
ROS API
Although most of ForteRC's sensors and actuators are already integrated in ROS, some additional features are available through its ROS API, starting with the low-level driver.
FORTERC_driver
FORTERC_driver is a ROS driver for the ForteRC platform, implemented on the Arduino MEGA ADK board. It deals with the omnidirectional kinematics, motor controllers and ultrasonic sensor readings. FORTERC_driver benefits from rosserial_arduino to publish and subscribe topics to the high-level layer. Read more about FORTERC_driver.Subscribed Topics
cmd_vel (geometry_msgs/Twist)- Velocity commands to FORTE-RC.
- Control right and left RGB head LEDs.
Published Topics
odometry (nav_msgs/Odometry)- Odometry data from the robot.
- Range data from the array of 16 ultrasonic sensors.
Provided tf Transforms
odom → base_link- Odometry transform from odom frame to FORTE-RC's center.
- Computed footprint of FORTE-RC on the ground (z=0). This pose is always regarding the center of the platform.
FORTERC_head
FORTERC_head is a simple adaptation of the ros_pololu_servo to ForteRC's head, controlled using a Micro Maestro 6-Channel USB Servo Controller. It deals with the control of both yaw (azimuth) and pitch (elevation). Read more about FORTERC_head.Subscribed Topics
pololu/command (ros_pololu_servo/MotorCommand)Published Topics
pololu/motor_states (ros_pololu_servo/MotorStateList)Robotic Manipulator MOVER 6
The Mover6 is a robotic manipulator with 6 degrees of freedom. CPR_Mover ros package was implemented to establish a robot control loop and connecting the robot arm using the USB-CAN adapter. Read more about PCAN-USB. Mover6.Subscribed Topics
CPRMoverErrorCodes (std_msgs/String)- Provides a string with the current status of the robot arms hardware joints, the error codes.
- Provides 6 joint values of the robot in radian.
Published Topics
CPRMoverJointVel (sensor_msgs/JointState)- When there are no points to replay from the actionServer, the robot reacts to the jog values in these messages. The allowed range is [-100.0 .. 100.0].
- The Mover reacts to commands received with these messages. Commands are: Connect / Reset / Enable / GripperOpen / GripperClose / Override ppp
Microsoft Kinect 2 NUI sensor
The Kinnect 2 is a Natural User Interface with HD resolution, Infrared array, depth camera and microphone array. To get more information about full specs please check Kinect2 specs. To use Kinect 2 on ros, libfreenect2 ros package was implemented. To establish the bridge beetween ROS and Kinect iai_kinect2 ros package was implemented. Read more about kinect2_Forte_RC.ForteRC Teleop
Forte_RC uses Wiimote to teleoperate the robot. The controller communicates wirelessly with the robot via short-range Bluetooth radio. joystick_drivers/wiimote ros package was implemented to allow communication between the remote and ROS. To operate robot movements simply launch forte_rc_wii_teleop.launch a pair the wiimote with the robot by pushing 1 & 2 buttons until the blue led's stop blinking. That's it. Enjoy!Published Topics
joy (joy/joy)- Topic on which Wiimote accelerometer, gyro, and button data are published. Axes are: linear AccelerationX/Y/Z, followed by angular velocityX/Y/Z.
- Information on the velocities provided to Forte_RC driver