First steps

To get started, we'll connect to Erle-Brain 3. When ordered with the WiFi option, Erle-Brain 3 ships preconfigured to generate a wireless network (in the 2.4GHz frequency band). In a nutshell, the brain acts as a router and allows a computer to get connected to it provided that they know the password (default password: holaerle). Alternatively, you can also use the Ethernet connection to easily connecto to Erle-Rover.

First thing is to scan for the Erle-Rover's WiFi network. In my case, I identified a network named erle-robotics-escarlata. Using the password holaerle does it.

For simplificty when working with traditional Ground Control Stations (GCS), our team has restricted the number of IPs allocated by the WiFi network to only one (particularly the 10.0.0.2). If you connect successfully to the wireless network, that's the IP you should get. If you need more, let us know and we'll help you figure it out.

Let's go ahead and SSH into Erle-Rover (password again, holaerle:

$ ssh erle@10.0.0.1 # password "holaerle", yes again
The authenticity of host '10.0.0.1 (10.0.0.1)' can't be established.
RSA key fingerprint is 14:ef:67:e3:2a:ad:69:b6:ec:63:b1:99:46:58:6c:41.
Are you sure you want to continue connecting (yes/no)? yes
Warning: Permanently added '10.0.0.1' (RSA) to the list of known hosts.
erle@10.0.0.1's password:

The programs included with the Debian GNU/Linux system are free software;
the exact distribution terms for each program are described in the
individual files in /usr/share/doc/*/copyright.

Debian GNU/Linux comes with ABSOLUTELY NO WARRANTY, to the extent
permitted by applicable law.
Last login: Tue Apr  5 15:34:31 2016 from 10.0.0.2
erle@erle-brain-3 ~ $ ls
AntennaTracker.elf  APMrover2.elf  ArduCopter.elf      ArduPlane.elf  gtk-tests  ros2_ws        spider.launch
APM                 apm.sh         ArduCopterHexa.elf  Documents      PXFmini    ros_catkin_ws  spider_ws

That's about it, you've got a prompt to your ground robot.

In case you didn't order the WiFi add-on, you can just hook an Ethernet cable to Erle-Brain 2 from your router. The eth0 interface has been configured to use DHCP so the Rover should get an IP from the router directly. You can easily figure out which IP corresponds to which machine with some command line magic but if you're in a hurry and would like to type less, we've got your back.

Erle-Rover comes preconfigured with an avahi service that allows anyone to track its brain using erle-brain-3.local name.

$ ping erle-brain-3.local
PING erle-brain-3.local (192.168.1.51): 56 data bytes
64 bytes from 192.168.1.51: icmp_seq=0 ttl=64 time=1.130 ms
64 bytes from 192.168.1.51: icmp_seq=1 ttl=64 time=0.658 ms
64 bytes from 192.168.1.51: icmp_seq=2 ttl=64 time=0.636 ms
64 bytes from 192.168.1.51: icmp_seq=3 ttl=64 time=0.703 ms
...

Which means that you can ssh into the Rover just by typing:

$ ssh erle@erle-brain-3.local # password, "holaerle"

Let's take a moment to inspect some of the ROS interfaces exposed by default:

Documenting each one of these interfaces is a work in progress. You can have a look at mavros ROS package to get a general understanding. If you need further assistance let us know and we'll happily help.

erle@erle-brain-3 ~ $ rosnode list
/mavros
/raspicam_node
/rosout
erle@erle-brain-3 ~ $ rostopic list
No handlers could be found for logger "rosout"
/camera/camera_info
/camera/image/compressed
/diagnostics
/mavlink/from
/mavlink/to
/mavros/actuator_control
/mavros/battery
/mavros/cam_imu_sync/cam_imu_stamp
/mavros/extended_state
/mavros/global_position/compass_hdg
/mavros/global_position/global
/mavros/global_position/local
/mavros/global_position/raw/fix
/mavros/global_position/raw/gps_vel
/mavros/global_position/rel_alt
/mavros/image/camera_image
/mavros/image/camera_image/compressed
/mavros/image/camera_image/compressed/parameter_descriptions
/mavros/image/camera_image/compressed/parameter_updates
/mavros/imu/atm_pressure
/mavros/imu/data
/mavros/imu/data_raw
/mavros/imu/mag
/mavros/imu/temperature
/mavros/local_position/local
/mavros/manual_control/control
/mavros/mission/waypoints
/mavros/mocap/pose
/mavros/px4flow/ground_distance
/mavros/px4flow/raw/optical_flow_rad
/mavros/px4flow/temperature
/mavros/radio_status
/mavros/rc/in
/mavros/rc/out
/mavros/rc/override
/mavros/safety_area/set
/mavros/setpoint_accel/accel
/mavros/setpoint_attitude/att_throttle
/mavros/setpoint_attitude/attitude
/mavros/setpoint_attitude/cmd_vel
/mavros/setpoint_position/local
/mavros/setpoint_velocity/cmd_vel
/mavros/state
/mavros/time_reference
/mavros/vfr_hud
/mavros/vibration/raw/vibration
/mavros/vision_pose/pose
/mavros/vision_pose/pose_cov
/mavros/vision_speed/speed_vector
/mavros/wind_estimation
/rosout
/rosout_agg
/tf
/tf_static

The following script shows how to move Erle-Rover around using the Robot Operating System. Feel free to play with the parameters around!

Note:
Among the software components that Erle-Rover includes, there's the autopilot (APM), a complex piece of software with about 700.000 lines of code. If you'd like to use more advance functions of the autopilot, refer to http://github.com/erlerobot/ardupilot for its source code. Additionally, you can always jump into our community and ask around.

#!/usr/bin/env python3

import rospy
from std_msgs.msg import String
import time
from mavros_msgs.msg import OverrideRCIn
from mavros_msgs.srv import SetMode
from mavros_msgs.srv import SetMode

# some variables to define the behavior of the robot (hardcoded, modify at your convenience)
throttle_channel=2
steer_channel=0

def autopilot_abstraction(speed='SLOW',direction='STRAIGHT', exec_time=1):
 pub = rospy.Publisher('mavros/rc/override', OverrideRCIn, queue_size=10)
 r = rospy.Rate(10) #10hz
 msg = OverrideRCIn()
 start = time.time()
 flag=True #time flag

 # Abstract the speed of the Rover
 if speed =='SLOW':
  msg.channels[throttle_channel]=1558
 elif speed =='NORMAL':
  msg.channels[throttle_channel]=1565
 elif speed == 'FAST':
  msg.channels[throttle_channel]=1570

 # Abstract the direction of the Rover
 if direction =='STRAIGHT':
  msg.channels[steer_channel]=1500
 elif direction =='LEFT':
  msg.channels[steer_channel]=1200
 elif direction == 'RIGHT':
  msg.channels[steer_channel]= 1800

 while not rospy.is_shutdown() and flag:
  sample_time=time.time()
  if ((sample_time - start) > exec_time):
   flag=False
  rospy.loginfo(msg)
  pub.publish(msg)
  r.sleep()

if __name__ == '__main__':
 rospy.init_node('tryrover_node', anonymous=True)
 rospy.wait_for_service('/mavros/set_mode')
 change_mode = rospy.ServiceProxy('/mavros/set_mode', SetMode)
 answer = change_mode(custom_mode='manual')
 print (answer)
 if 'True' in str(answer):
  try:
   autopilot_abstraction('SLOW','RIGHT', 2)
   autopilot_abstraction('SLOW','STRAIGHT', 2)
   autopilot_abstraction('SLOW','LEFT', 2)

  except rospy.ROSInterruptException: pass