Skip to content

Making a controller (Python)

Ulysse Vautier edited this page May 10, 2018 · 19 revisions

Structure of the node

To make your own controller please follow the convention :

- sailrobot
    - scripts
        - (main node file + controller class)

Nothing stops you from separating the controller class and the main node file. The main node file only needs a couple of lines to work.

Controller Class

To build your own controller class, derive from controller.py. All you have to do is implement the control method and return a geometry_msgs::Twist ROS Message according to the Arduino Mode :

from controller import Controller
from controller import MODE
import rospy

class My_Controller(Controller):
        def __init__(self, name, looprate):
		Controller.__init__(self,name, looprate, <MODE>)
	def control(self):
		#Add your control algorithm here
                return TwistMessage

Edit <MODE> according to the Arduino Mode you want to use.

Protected Members

You have access to multiple methods and variables to help you implement your own controller :

  • gpsMsg (gps_common::GPSFix) : message containing GPS information of the boat
  • imuMsg (sensor_msgs::Imu) : message containing IMU information of the boat
  • windMsg (geometry_msgs::Pose2D) : message containing Wind Sensor information of the boat
  • velMsg (geometry_msgs::Twist) : message containing velocity of the boat from the IMU
  • rudderAngle (float) : float containing the actual rudder angle
  • sailAngle (float) : float containing the actual sail angle
  • n (ros::NodeHandle) : In case you want to subscribe to other topics

In case the boat has a 2nd rudder, it can be accessed by :

  • rudder2Angle (float) : float containing the actual 2nd rudder angle

For instance, if you want to use the apparent wind angle, use self.windMsg.theta. These messages are automatically received by the controller class at initialization.

Main Node

Once you have finished coding your controller class, all you need now is to build the node file. This node basically has to create your Controller object and launch it. Here is a template of a node file :

if __name__ == '__main__':
	try:
		controller = My_Controller('controller', 10)
		while not rospy.is_shutdown():
			controller.loop()
	except rospy.ROSInterruptException:

		pass