Clover adaptation

How we adapt clover platform to our own use

Integration with the Clover platform can be simple and totally intuitive. The main aspects of Clover that we will work on are block programming, simulation and real-world application. The cycle of coding, simulation and real-world drone application is very useful for development and learning, something that will be important for decision making.

The developed algorithms will be simulated through the Clover implementation in Gazebo. One of the advantages is the fidelity to the real Clover, by the PX4 flight controller simulation, which uses the MAVROS interface for the MAVLINK protocol. The intention is to allow the planning and simulation of the mission, enabling a better organization of the swarm and the previous analysis of failures. Finally, the application of developed and tested codes in the simulation must be minimally modified for the application in the real Clover. This concept is already used by Clover with MAVROS communication with the controller or with a base.

To make our project work, we need to make some changes to the Clover tools. Specifically the simulation launch, namespaces, xacro and others for the swarm implementation.

LED's

When dealing with the LED's we found problems in the implementation, to solve them we had to change the topic names and how the node was subscribing to the Topic, in other words we changed the ROS names. Below one of the changes is shown. We had to change the set_leds to led/set_leds, as a consequence of how the Gazebo advertise the service.

This change is also related to how the Node was referenced, before it was a namespace, so it was always overwriting itself.

This last LED-related change is also linked to the xacro, next topic. This ... was overwriting a namespace without a namespace, so that it prevented the implementation for multiple Clovers.

Xacro

A important change would be in relation to gazebo's Xacro, as described in the MAVLink interface where it follows a modern hybrid publish-subscribe and point-to-point design pattern: Data streams are sent / published as topics while configuration sub-protocols such as the mission protocol or parameter protocol are point-to-point with retransmission. More answers can be found at MAVLink. That said, we have changed mavlink_tcp_port so that this port is no longer fixed, making it possible to implement the swarm, because now the MAVLink parameters and interface work for all Clovers. This argument came from ~/catkin_ws/src/swarm_in_blocks/swarm_in_blocks/launch/simulation/clover_simulated.launch

We launch a block similar to Clover's structure, the gazebo is also initialized, both are launched only once. Furthermore, we made a Python file that launches the Clovers in the desired way, with the parameters commented in the previous paragraph. esse arquivo é responsavel por chamar o arquivo clover_simulated.py.

TF2-ROS

According to the ROS Wiki:

"TF is a package that lets the user keep track of multiple coordinate frames over time. tf maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time."

Here again we had problems with the ROS names, which by definition: Assign a value from the parameter server, with the default value. This method tries to retrieve the indicated parameter value from the parameter server, storing the result in param_val. If the value cannot be retrieved from the server, the default param_val is used. That said, we had to create them so that each Clover would publish its own parameter, because even though they make up a collective role as swarm each one must pass its own parameters.

We also included and/or changed standard reference frames, service clients, telemetry subscribers and setpoint publishers. The entire code can be found at ~/catkin_ws/src/clover/clover/src/simple_offboard.cpp.

// Default reference frames
	std::map<string, string> default_reference_frames;
	default_reference_frames[body.child_frame_id] = local_frame;
	default_reference_frames[fcu_frame] = local_frame;
	if (!target.child_frame_id.empty()) default_reference_frames[target.child_frame_id] = local_frame;
	reference_frames.insert(default_reference_frames.begin(), default_reference_frames.end()); // merge defaults

// Service clients
	arming = nh.serviceClient<mavros_msgs::CommandBool>(mavros + "/cmd/arming");
	set_mode = nh.serviceClient<mavros_msgs::SetMode>(mavros + "/set_mode");

// Telemetry subscribers
	auto state_sub = nh.subscribe(mavros + "/state", 1, &handleState);
	auto velocity_sub = nh.subscribe(mavros + "/local_position/velocity_body", 1, &handleMessage<TwistStamped, velocity>);
	auto global_position_sub = nh.subscribe(mavros + "/global_position/global", 1, &handleMessage<NavSatFix, global_position>);
	auto battery_sub = nh.subscribe(mavros + "/battery", 1, &handleMessage<BatteryState, battery>);
	auto statustext_sub = nh.subscribe(mavros + "/statustext/recv", 1, &handleMessage<mavros_msgs::StatusText, statustext>);
	auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
	auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);

// Setpoint publishers
	position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
	position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
	attitude_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_attitude/attitude", 1);
	attitude_raw_pub = nh.advertise<AttitudeTarget>(mavros + "/setpoint_raw/attitude", 1);
	rates_pub = nh.advertise<TwistStamped>(mavros + "/setpoint_attitude/cmd_vel", 1);
	thrust_pub = nh.advertise<Thrust>(mavros + "/setpoint_attitude/thrust", 1);

Launch

To simulate the Swarm of Clovers we need to make a specific file that launches multiple drones. The one that makes this happen is the simulation.launch script. Through it the user can set the number of drones, the initial formation and if the led, camera, rangefinder and flashlight will be working. It is worth mentioning that other modifications like the gazebo world can also be made through it. A Python file called launch.py assists in this task. It launch each vehicle on the right coordinate based on the formation . We launch a block similar to Clover's structure, the gazebo is also initialized, both are launched only once.

Something important to note is that this file will also set a MAVLink tcp port and MAVROS address. We had to change the ports that MAVROS has access to, as shown below, this happened in this file and in the startup file as well. Finally, some essential information will also be saved for the use of other files in the clover folder and swarm_in_blocks.

clover_simulated.launch
    <!-- Gazebo -->
    <arg name="mavlink_tcp_port" value="$(eval 4560 + arg('ID'))"/>

    <!-- MAVROS -->
    <arg name="remote" value="$(eval 14800 + arg('ID'))"/>
    <arg name="local" value="$(eval 15000 + arg('ID'))"/>
    <arg name="fcu_url" default="udp://:$(arg remote)@$(arg simulator_ip):$(arg local)"/>

Automatic roslaunch

The pre-configured image for the Raspberry Pi of Clover defaults to automatically running the roslaunch for a single Clover in order to improve convenience. However, in our application, we need to run our own roslaunch. Therefore, we must execute the following command in the terminal of the Clover's Raspberry Pi to disable this feature:

Last updated