Nantes Université

Skip to content
Extraits de code Groupes Projets

Comparer les révisions

Les modifications sont affichées comme si la révision source était fusionnée avec la révision cible. En savoir plus sur la comparaison des révisions.

Source

Sélectionner le projet cible
No results found

Cible

Sélectionner le projet cible
  • ls2n-drones/ls2n_drone_armada
1 résultat
Afficher les modifications
Validations sur la source (9)
......@@ -47,6 +47,30 @@ ament_target_dependencies(
# Install the executable
install(TARGETS armada_controller DESTINATION lib/ls2n_drone_armada)
# Create the simplified ROS node executable
add_executable(armada_simple_controller src/armada_simple_controller_node.cpp)
# Include directories for the executable
target_include_directories(armada_simple_controller PRIVATE include
include/${PROJECT_NAME})
# Link the executable to Eigen
target_link_libraries(armada_simple_controller Eigen3::Eigen)
# ROS2 dependencies for the executable
ament_target_dependencies(
armada_simple_controller
rclcpp
geometry_msgs
nav_msgs
std_srvs
ls2n_drone_interfaces
trajectory_msgs
rcl_interfaces)
# Install the executable
install(TARGETS armada_simple_controller DESTINATION lib/ls2n_drone_armada)
# Install the library
install(
TARGETS armada_controller_core
......
#ifndef ARMADA_SIMPLE_CONTROLLER_NODE_HPP_
#define ARMADA_SIMPLE_CONTROLLER_NODE_HPP_
#include <geometry_msgs/msg/vector3.hpp>
#include <ls2n_drone_interfaces/msg/joystick.hpp>
#include <ls2n_drone_interfaces/srv/controller_selection.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/empty.hpp>
#include <trajectory_msgs/msg/joint_trajectory.hpp>
#include <Eigen/Dense>
#include <memory>
#include <vector>
/**
* @brief Simple ROS node for the ARMADA controller with joystick control only
*/
class ArmadaSimpleControllerNode : public rclcpp::Node {
public:
/**
* @brief Constructor
*/
ArmadaSimpleControllerNode();
private:
/**
* @brief Callback for drone odometry
* @param msg Odometry message
* @param drone_index Index of the drone
*/
void droneOdometryCallback(const nav_msgs::msg::Odometry::SharedPtr msg,
size_t drone_index);
/**
* @brief Callback for joystick messages
* @param msg Joystick message
*/
void
joystickCallback(const ls2n_drone_interfaces::msg::Joystick::SharedPtr msg);
/**
* @brief Timer callback for updating position based on joystick input
*/
void joystickUpdateTimer();
/**
* @brief Service callback to activate joystick control mode
* @param request Empty request
* @param response Empty response
*/
void activateJoystickControl(
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
std::shared_ptr<std_srvs::srv::Empty::Response> response);
/**
* @brief Send desired positions to drones
*/
void sendDesiredPositions();
// Configuration parameters
int num_drones_;
std::vector<std::string> drone_names_;
double max_joystick_velocity_;
// Drone states
struct DroneState {
Eigen::Vector3d position;
Eigen::Vector4d orientation;
Eigen::Vector3d velocity;
};
std::vector<DroneState> drone_states_;
std::vector<bool> odometry_received_;
// Relative positions to maintain
std::vector<Eigen::Vector3d> relative_positions_;
bool positions_recorded_ = false;
// Joystick control state
bool joystick_active_ = false;
Eigen::Vector3d joystick_velocity_command_;
Eigen::Vector3d leader_reference_position_;
rclcpp::Time last_joystick_update_time_;
rclcpp::TimerBase::SharedPtr joystick_timer_;
// ROS publishers
std::vector<rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr>
trajectory_publishers_;
// ROS subscribers
std::vector<rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr>
drone_odometry_subscribers_;
rclcpp::Subscription<ls2n_drone_interfaces::msg::Joystick>::SharedPtr
joystick_subscriber_;
// ROS services
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr
activate_joystick_control_service_;
std::vector<rclcpp::Client<
ls2n_drone_interfaces::srv::ControllerSelection>::SharedPtr>
controller_selection_clients_;
};
#endif // ARMADA_SIMPLE_CONTROLLER_NODE_HPP_
#include "armada_controller/armada_simple_controller_node.hpp"
#include <chrono>
#include <memory>
#include <string>
#include <vector>
using namespace std::chrono_literals;
ArmadaSimpleControllerNode::ArmadaSimpleControllerNode()
: Node("armada_simple_controller") {
RCLCPP_INFO(get_logger(), "Starting armada simple controller node");
// Declare parameters
declare_parameter<std::vector<std::string>>("drones_to_control", {""});
declare_parameter<double>("max_joystick_velocity", 0.5);
// Get parameters
drone_names_ = get_parameter("drones_to_control").as_string_array();
max_joystick_velocity_ = get_parameter("max_joystick_velocity").as_double();
num_drones_ = static_cast<int>(drone_names_.size());
RCLCPP_INFO(get_logger(), "Controlling %d drones", num_drones_);
// Initialize states
drone_states_.resize(num_drones_);
relative_positions_.resize(num_drones_);
odometry_received_.resize(num_drones_, false);
// Initialize joystick control
joystick_velocity_command_ = Eigen::Vector3d::Zero();
leader_reference_position_ = Eigen::Vector3d::Zero();
// QoS profile
auto qos = rclcpp::QoS(rclcpp::SensorDataQoS());
qos.keep_last(1);
// Create subscribers and publishers
drone_odometry_subscribers_.resize(num_drones_);
trajectory_publishers_.resize(num_drones_);
controller_selection_clients_.resize(num_drones_);
for (int i = 0; i < num_drones_; ++i) {
// Subscribers for drone odometry
drone_odometry_subscribers_[i] =
create_subscription<nav_msgs::msg::Odometry>(
"/" + drone_names_[i] + "/EKF/odom", qos,
[this, i](const nav_msgs::msg::Odometry::SharedPtr msg) {
this->droneOdometryCallback(msg, i);
});
// Publishers for trajectory commands
trajectory_publishers_[i] = create_publisher<trajectory_msgs::msg::JointTrajectory>(
"/" + drone_names_[i] + "/ref_traj", qos);
// Clients for controller selection
controller_selection_clients_[i] =
create_client<ls2n_drone_interfaces::srv::ControllerSelection>(
"/" + drone_names_[i] + "/controller_selection");
}
// Joystick subscriber
joystick_subscriber_ =
create_subscription<ls2n_drone_interfaces::msg::Joystick>(
"/CommandCenter/joystick", qos,
[this](const ls2n_drone_interfaces::msg::Joystick::SharedPtr msg) {
this->joystickCallback(msg);
});
// Joystick control service
activate_joystick_control_service_ = create_service<std_srvs::srv::Empty>(
"/Armada/ActivateSimpleJoystickControl",
[this](const std::shared_ptr<std_srvs::srv::Empty::Request> request,
std::shared_ptr<std_srvs::srv::Empty::Response> response) {
this->activateJoystickControl(request, response);
});
// Create joystick update timer (100Hz)
joystick_timer_ = create_wall_timer(10ms, [this]() {
if (joystick_active_) {
this->joystickUpdateTimer();
}
});
}
void ArmadaSimpleControllerNode::droneOdometryCallback(
const nav_msgs::msg::Odometry::SharedPtr msg, size_t drone_index) {
// Update drone state
drone_states_[drone_index].position =
Eigen::Vector3d(msg->pose.pose.position.x, msg->pose.pose.position.y,
msg->pose.pose.position.z);
drone_states_[drone_index].orientation = Eigen::Vector4d(
msg->pose.pose.orientation.w, msg->pose.pose.orientation.x,
msg->pose.pose.orientation.y, msg->pose.pose.orientation.z);
drone_states_[drone_index].velocity =
Eigen::Vector3d(msg->twist.twist.linear.x, msg->twist.twist.linear.y,
msg->twist.twist.linear.z);
odometry_received_[drone_index] = true;
}
void ArmadaSimpleControllerNode::joystickCallback(
const ls2n_drone_interfaces::msg::Joystick::SharedPtr msg) {
if (!joystick_active_) {
return;
}
// Scale the joystick input to get velocity commands
joystick_velocity_command_.x() =
msg->axis_left_horizontal * max_joystick_velocity_;
joystick_velocity_command_.y() =
-msg->axis_left_vertical * max_joystick_velocity_;
// Use right stick for vertical movement
joystick_velocity_command_.z() =
msg->axis_right_vertical * max_joystick_velocity_;
}
void ArmadaSimpleControllerNode::joystickUpdateTimer() {
// Calculate time since last update
auto current_time = this->now();
double dt = 0.01; // Default 10ms
if (last_joystick_update_time_ != rclcpp::Time(0, 0, RCL_ROS_TIME)) {
dt = (current_time - last_joystick_update_time_).seconds();
}
last_joystick_update_time_ = current_time;
// Update reference position of leader based on joystick input
leader_reference_position_ += joystick_velocity_command_ * dt;
// Send positions to all drones
sendDesiredPositions();
}
void ArmadaSimpleControllerNode::activateJoystickControl(
const std::shared_ptr<std_srvs::srv::Empty::Request>,
std::shared_ptr<std_srvs::srv::Empty::Response>) {
RCLCPP_INFO(get_logger(), "Activate simple joystick control request made");
// Check if we have received odometry for all drones
for (size_t i = 0; i < odometry_received_.size(); ++i) {
if (!odometry_received_[i]) {
RCLCPP_ERROR(get_logger(),
"Cannot activate joystick control, odometry feedback for "
"drone %zu is missing!",
i + 1);
return;
}
}
// Send controller selection request to all drones
auto request = std::make_shared<
ls2n_drone_interfaces::srv::ControllerSelection::Request>();
request->controller_name = "position_pid";
for (size_t i = 0; i < controller_selection_clients_.size(); ++i) {
if (!controller_selection_clients_[i]->wait_for_service(
std::chrono::seconds(1))) {
RCLCPP_ERROR(get_logger(),
"Controller selection service for drone %zu not available",
i + 1);
return;
}
RCLCPP_INFO(get_logger(),
"Sending position_pid controller selection to drone %zu", i + 1);
controller_selection_clients_[i]->async_send_request(request);
}
// Set leader reference position to current position of first drone
leader_reference_position_ = drone_states_[0].position;
// Record relative positions
for (int i = 0; i < num_drones_; ++i) {
relative_positions_[i] = drone_states_[i].position - drone_states_[0].position;
}
positions_recorded_ = true;
// Initialize joystick state
joystick_velocity_command_ = Eigen::Vector3d::Zero();
last_joystick_update_time_ = this->now();
// Activate control
joystick_active_ = true;
RCLCPP_INFO(get_logger(), "Simple joystick control mode activated!");
}
void ArmadaSimpleControllerNode::sendDesiredPositions() {
if (!positions_recorded_) {
return;
}
// Create and send trajectory message for each drone
for (int i = 0; i < num_drones_; ++i) {
auto traj_msg = std::make_unique<trajectory_msgs::msg::JointTrajectory>();
traj_msg->header.stamp = this->now();
// Add joints
traj_msg->joint_names = {"x", "y", "z", "yaw"};
// Add points
trajectory_msgs::msg::JointTrajectoryPoint point;
// Compute desired position for this drone based on leader reference and relative position
Eigen::Vector3d desired_position = leader_reference_position_ + relative_positions_[i];
// Add positions
point.positions = {desired_position.x(), desired_position.y(), desired_position.z(), 0.0}; // constant yaw
// Add velocities
point.velocities = {joystick_velocity_command_.x(), joystick_velocity_command_.y(), joystick_velocity_command_.z(), 0.0};
// Add accelerations (always zero)
point.accelerations = {0.0, 0.0, 0.0, 0.0};
// Add time from start
point.time_from_start = rclcpp::Duration(0, 0);
traj_msg->points.push_back(point);
// Publish the trajectory
trajectory_publishers_[i]->publish(*traj_msg);
}
}
int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
auto node = std::make_shared<ArmadaSimpleControllerNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
......@@ -3,13 +3,15 @@ from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
)
from launch.substitutions import LaunchConfiguration
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from ament_index_python.packages import get_package_share_directory
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
# Common launch arguments for both real and simulated drones
platform_mass_launch_arg = DeclareLaunchArgument(
"platform_mass",
default_value="0.993",
......@@ -24,10 +26,22 @@ def generate_launch_description():
max_joystick_velocity_launch_arg = DeclareLaunchArgument(
"max_joystick_velocity",
default_value="0.01",
default_value="0.5",
description="Maximum velocity in m/s for joystick control",
)
cable_length_launch_arg = DeclareLaunchArgument(
"cable_length",
default_value="1.6",
description="Length of a cable [m]",
)
drones_to_control_launch_arg = DeclareLaunchArgument(
"drones_to_control",
default_value="['Crazy2fly8', 'Crazy2fly6', 'Crazy2fly7']",
description="List of the drone namespaces to control",
)
return LaunchDescription(
[
DeclareLaunchArgument(
......@@ -43,29 +57,28 @@ def generate_launch_description():
),
DeclareLaunchArgument(
"joy_config_version",
default_value="CONFIG_1",
default_value="joystick_config3.yaml",
description="Joystick configuration",
),
platform_mass_launch_arg,
drone_masses_launch_arg,
max_joystick_velocity_launch_arg,
cable_length_launch_arg,
drones_to_control_launch_arg,
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
get_package_share_directory("ls2n_drone_command_center"),
"/mocap.launch.py",
]
)
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
get_package_share_directory("ls2n_drone_command_center"),
"/joystick.launch.py",
PathJoinSubstitution(
[
FindPackageShare("ls2n_drone_joystick"),
"launch",
"joystick.launch.py",
]
)
]
),
launch_arguments={
"joy_config_version": LaunchConfiguration("joy_config_version")
"joy_config_file": LaunchConfiguration("joy_config_version")
}.items(),
),
Node(
......@@ -73,33 +86,23 @@ def generate_launch_description():
executable="multi_control",
namespace="CommandCenter",
parameters=[
{"drones_to_control": ["Crazy2fly8", "Crazy2fly6", "Crazy2fly7"]}
{"drones_to_control": LaunchConfiguration("drones_to_control")}
],
),
Node(
package="ls2n_drone_armada",
executable="armada_control",
executable="armada_controller",
parameters=[
{
"drones_to_control": ["Crazy2fly8", "Crazy2fly6", "Crazy2fly7"],
"cable_length": 1.6,
"drones_to_control": LaunchConfiguration("drones_to_control"),
"cable_length": LaunchConfiguration("cable_length"),
"platform_mass": LaunchConfiguration("platform_mass"),
"drone_masses": [1.0, 1.0, 1.0],
"drone_masses": LaunchConfiguration("drone_masses"),
"max_joystick_velocity": LaunchConfiguration(
"max_joystick_velocity"
),
}
],
),
Node(
package="ls2n_drone_armada",
executable="mc_node",
namespace="CommandCenter",
),
Node(
package="ls2n_drone_armada",
executable="trajectory_publisher",
parameters=[{"trajectory": "square"}],
),
]
)
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
)
from launch.substitutions import LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
from launch_ros.actions import Node
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
max_joystick_velocity_launch_arg = DeclareLaunchArgument(
"max_joystick_velocity",
default_value="0.01",
description="Maximum velocity in m/s for joystick control",
)
return LaunchDescription(
[
DeclareLaunchArgument(
"drone_model",
default_value="crazy2fly",
description="Drone model",
choices=["crazy2fly"],
),
DeclareLaunchArgument(
"number_of_drones",
default_value="3",
description="Number of drones",
),
DeclareLaunchArgument(
"joy_config_version",
default_value="CONFIG_1",
description="Joystick configuration",
),
max_joystick_velocity_launch_arg,
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
get_package_share_directory("ls2n_drone_command_center"),
"/mocap.launch.py",
]
)
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
get_package_share_directory("ls2n_drone_command_center"),
"/joystick.launch.py",
]
),
launch_arguments={
"joy_config_version": LaunchConfiguration("joy_config_version")
}.items(),
),
Node(
package="ls2n_drone_command_center",
executable="multi_control",
namespace="CommandCenter",
parameters=[
{"drones_to_control": ["Crazy2fly8", "Crazy2fly6", "Crazy2fly7"]}
],
),
Node(
package="ls2n_drone_armada",
executable="armada_simple_controller",
parameters=[
{
"drones_to_control": ["Crazy2fly8", "Crazy2fly6", "Crazy2fly7"],
"max_joystick_velocity": LaunchConfiguration(
"max_joystick_velocity"
),
}
],
),
Node(
package="ls2n_drone_armada",
executable="mc_node",
namespace="CommandCenter",
),
]
)
......@@ -10,6 +10,8 @@ Brief: ROS2 launch file for the ARMADA PX4 SITL / Gazebo simulation
License: Apache 2.0
"""
# TODO: Why joystick control doesn't work with the new launch file?
import os
from launch import LaunchDescription, LaunchDescriptionEntity, LaunchContext
from launch.actions import (
......@@ -137,84 +139,35 @@ def launch_setup(
for i in range(nb_of_drones)
]
# Joystick
joy_launch = IncludeLaunchDescription(
# Include armada_control.launch.py for common functionality
armada_control_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("ls2n_drone_joystick"),
FindPackageShare("ls2n_drone_armada"),
"launch",
"joystick.launch.py",
"armada_control.launch.py",
]
)
]
),
launch_arguments={
"joy_config_file": LaunchConfiguration("joy_config_file")
"drone_model": LaunchConfiguration("drone_model"),
"number_of_drones": LaunchConfiguration("number_of_drones"),
"platform_mass": LaunchConfiguration("platform_mass"),
"drone_masses": LaunchConfiguration("drone_masses"),
"cable_length": LaunchConfiguration("cable_length"),
"drones_to_control": LaunchConfiguration("drones_to_control"),
"joy_config_version": "joystick_config3.yaml",
}.items(),
)
# Armada trajectory
traj_file_name = os.path.join(
get_package_share_directory("ls2n_drone_armada"),
"trajectories",
"square.traj.pickle",
)
traj_pub__launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("ls2n_drone_trajectories"),
"launch",
"traj_pub.launch.py",
]
)
]
),
launch_arguments={"drone_name": "Armada", "traj_file": traj_file_name}.items(),
)
# Command center
cmd_center_node = Node(
package="ls2n_drone_command_center",
executable="multi_control",
namespace="CommandCenter",
parameters=[{"drones_to_control": LaunchConfiguration("drones_to_control")}],
)
# Armada controller
armada_ctrl_node = Node(
package="ls2n_drone_armada",
executable="armada_controller",
parameters=[
{
"drones_to_control": LaunchConfiguration("drones_to_control"),
"cable_length": LaunchConfiguration("cable_length"),
"platform_mass": LaunchConfiguration("platform_mass"),
"drone_masses": LaunchConfiguration("drone_masses"),
}
],
)
# Keep alive node
keep_alive_node = Node(
package="ls2n_drone_armada",
executable="keep_alive_node.py",
name="keep_alive_node",
output="screen",
)
launch_entities = [
gz_bridge,
odometry_transformer,
px4_sitl_multidrone_launch,
joy_launch,
traj_pub__launch,
cmd_center_node,
armada_ctrl_node,
keep_alive_node,
armada_control_launch,
]
launch_entities += controllers_launches
......@@ -228,7 +181,8 @@ def generate_launch_description() -> LaunchDescription:
LaunchDescription: launch description
"""
# Declare launch arguments
# Only declare SITL-specific launch arguments
# (common arguments are declared in armada_control.launch.py)
drone_model_launch_arg = DeclareLaunchArgument(
"drone_model",
default_value="crazy2fly",
......@@ -249,12 +203,6 @@ def generate_launch_description() -> LaunchDescription:
description="List of the drone namespaces to control",
)
cable_length_launch_arg = DeclareLaunchArgument(
"cable_length",
default_value="1.25",
description="Length of a cable [m]",
)
platform_mass_launch_arg = DeclareLaunchArgument(
"platform_mass",
default_value="1.0",
......@@ -267,10 +215,10 @@ def generate_launch_description() -> LaunchDescription:
description="Masses of the drones [kg]",
)
joy_cfg_launch_arg = DeclareLaunchArgument(
"joy_config_file",
default_value="joystick_config3.yaml",
description="Joystick configuration file to use",
cable_length_launch_arg = DeclareLaunchArgument(
"cable_length",
default_value="1.25",
description="Length of a cable [m]",
)
return LaunchDescription(
......@@ -278,10 +226,9 @@ def generate_launch_description() -> LaunchDescription:
drone_model_launch_arg,
nb_of_drones_launch_arg,
drones_to_ctrl_launch_arg,
cable_length_launch_arg,
platform_mass_launch_arg,
drone_masses_launch_arg,
joy_cfg_launch_arg,
cable_length_launch_arg,
OpaqueFunction(function=launch_setup),
]
)