From 67c49303150b61403ad49018f617d870b703221e Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 30 Dec 2014 10:21:21 +0100 Subject: [PATCH 1/4] added mixer node --- src/platforms/ros/nodes/mc_mixer.cpp | 72 ++++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 src/platforms/ros/nodes/mc_mixer.cpp diff --git a/src/platforms/ros/nodes/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer.cpp new file mode 100644 index 0000000000..ddafde3b96 --- /dev/null +++ b/src/platforms/ros/nodes/mc_mixer.cpp @@ -0,0 +1,72 @@ +e/**************************************************************************** + * + * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file att_estimator.cpp + * Dummy attitude estimator that forwards attitude from gazebo to px4 topic + * + * @author Roman Bapst +*/ + #include "ros/ros.h" + + struct { + float control[8]; + }inputs; + + struct { + float control[8]; + }outputs; + +void mix(void *input) { + + +} + + void actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg) +{ + // read message + memcpy(inputs,msg,sizeof(inputs)); + // mix + +} + + int main(int argc, char **argv) +{ + ros::init(argc, argv, "mc_mixer"); + ros::NodeHandle n; + ros::Subscriber sub = n.subscribe("actuator_controls_0", 1000, actuatorControlsCallback); + + ros::spin(); + + return 0; +} From 484020177d947bf308466cb0bd5342cee0dd014a Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 30 Dec 2014 11:06:40 +0100 Subject: [PATCH 2/4] further progress on mixer node --- CMakeLists.txt | 9 +++ src/platforms/ros/nodes/mc_mixer.cpp | 101 +++++++++++++++++++++++++-- 2 files changed, 106 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5e0f9b29c9..57d1bc440f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -182,6 +182,15 @@ target_link_libraries(att_estimator px4 ) +## Multicopter Mixer dummy +add_executable(mc_mixer + src/platforms/ros/nodes/mc_mixer.cpp) +add_dependencies(mc_mixer px4_generate_messages_cpp) +target_link_libraries(mc_mixer + ${catkin_LIBRARIES} + px4 +) + ############# ## Install ## diff --git a/src/platforms/ros/nodes/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer.cpp index ddafde3b96..a131440a89 100644 --- a/src/platforms/ros/nodes/mc_mixer.cpp +++ b/src/platforms/ros/nodes/mc_mixer.cpp @@ -1,4 +1,4 @@ -e/**************************************************************************** +/**************************************************************************** * * Copyright (c) 2014 PX4 Development Team. All rights reserved. * @@ -37,7 +37,19 @@ e/**************************************************************************** * * @author Roman Bapst */ - #include "ros/ros.h" + #include + #include + #include + #include + + #define _rotor_count 4 + + struct Rotor { + float roll_scale; + float pitch_scale; + float yaw_scale; +}; + struct { float control[8]; @@ -47,16 +59,96 @@ e/**************************************************************************** float control[8]; }outputs; -void mix(void *input) { + +const Rotor _config_x[] = { + { 0.000000, -1.000000, -1.00 }, + { -0.000000, 1.000000, -1.00 }, + { 1.000000, 0.000000, 1.00 }, + { -1.000000, 0.000000, 1.00 }, +}; + + const Rotor *_rotors = { &_config_x[0] + + }; +void mix() { + float roll = math::constrain(inputs.control[0], -1.0f, 1.0f); + float pitch = math::constrain(inputs.control[1], -1.0f, 1.0f); + float yaw = math::constrain(inputs.control[2], -1.0f, 1.0f); + float thrust = math::constrain(inputs.control[3], 0.0f, 1.0f); + float min_out = 0.0f; + float max_out = 0.0f; + + /* perform initial mix pass yielding unbounded outputs, ignore yaw */ + for (unsigned i = 0; i < _rotor_count; i++) { + float out = roll * _rotors[i].roll_scale + + pitch * _rotors[i].pitch_scale + thrust; + + /* limit yaw if it causes outputs clipping */ + if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) { + yaw = -out / _rotors[i].yaw_scale; + } + + /* calculate min and max output values */ + if (out < min_out) { + min_out = out; + } + if (out > max_out) { + max_out = out; + } + + outputs.control[i] = out; + } + /* scale down roll/pitch controls if some outputs are negative, don't add yaw, keep total thrust */ + if (min_out < 0.0f) { + float scale_in = thrust / (thrust - min_out); + + /* mix again with adjusted controls */ + for (unsigned i = 0; i < _rotor_count; i++) { + outputs.control[i] = scale_in + * (roll * _rotors[i].roll_scale + + pitch * _rotors[i].pitch_scale) + thrust; + } + + } else { + /* roll/pitch mixed without limiting, add yaw control */ + for (unsigned i = 0; i < _rotor_count; i++) { + outputs.control[i] += yaw * _rotors[i].yaw_scale; + } + } + + /* scale down all outputs if some outputs are too large, reduce total thrust */ + float scale_out; + if (max_out > 1.0f) { + scale_out = 1.0f / max_out; + + } else { + scale_out = 1.0f; + } + + /* scale outputs to range _idle_speed..1, and do final limiting */ + for (unsigned i = 0; i < _rotor_count; i++) { + outputs.control[i] = math::constrain(outputs.control[i], 0.0f, 1.0f); + } } void actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg) { // read message - memcpy(inputs,msg,sizeof(inputs)); + for(int i = 0;i < msg.NUM_ACTUATOR_CONTROLS;i++) { + inputs.control[i] = msg.control[i]; + } + // mix + mix(); + + // publish message + mav_msgs::MotorSpeed rotor_vel_msg; + for (int i = 0; i < _rotor_count; i++) { + rotor_vel_msg.motor_speed.push_back(outputs.control[i]); + } + pub.publish(rotor_vel_msg); } @@ -65,6 +157,7 @@ void mix(void *input) { ros::init(argc, argv, "mc_mixer"); ros::NodeHandle n; ros::Subscriber sub = n.subscribe("actuator_controls_0", 1000, actuatorControlsCallback); + ros::Publisher pub = n.advertise("mixed_motor_commands",10); ros::spin(); From fa1f09b850f754ff3e0da7f4c5e56e3ee58fce11 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 30 Dec 2014 11:34:37 +0100 Subject: [PATCH 3/4] made class for mc_mixer and moved into folder --- .../ros/nodes/{ => mc_mixer}/mc_mixer.cpp | 61 +++++++++++++------ 1 file changed, 44 insertions(+), 17 deletions(-) rename src/platforms/ros/nodes/{ => mc_mixer}/mc_mixer.cpp (81%) diff --git a/src/platforms/ros/nodes/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp similarity index 81% rename from src/platforms/ros/nodes/mc_mixer.cpp rename to src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp index a131440a89..79eaf19e52 100644 --- a/src/platforms/ros/nodes/mc_mixer.cpp +++ b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp @@ -41,38 +41,67 @@ #include #include #include + + class MultirotorMixer { +public: - #define _rotor_count 4 + MultirotorMixer(); - struct Rotor { - float roll_scale; - float pitch_scale; - float yaw_scale; -}; + struct Rotor { + float roll_scale; + float pitch_scale; + float yaw_scale; + }; - struct { - float control[8]; + void mix(); + void actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg); + +private: + + ros::NodeHandle _n; + ros::Subscriber _sub; + ros::Publisher _pub; + + const Rotor *_rotors; + + unsigned _rotor_count; + + struct { + float control[6]; }inputs; struct { - float control[8]; + float control[6]; }outputs; -const Rotor _config_x[] = { + +}; + + + +const MultirotorMixer::Rotor _config_x[] = { { 0.000000, -1.000000, -1.00 }, { -0.000000, 1.000000, -1.00 }, { 1.000000, 0.000000, 1.00 }, { -1.000000, 0.000000, 1.00 }, }; - const Rotor *_rotors = { &_config_x[0] + const MultirotorMixer::Rotor *_config_index = { &_config_x[0] }; +MultirotorMixer::MultirotorMixer(): + _rotor_count(4), + _rotors(_config_index) +{ + _sub = _n.subscribe("actuator_controls_0", 1000, &MultirotorMixer::actuatorControlsCallback,this); + _pub = _n.advertise("mixed_motor_commands",10); +} -void mix() { + +void MultirotorMixer::mix() { float roll = math::constrain(inputs.control[0], -1.0f, 1.0f); float pitch = math::constrain(inputs.control[1], -1.0f, 1.0f); float yaw = math::constrain(inputs.control[2], -1.0f, 1.0f); @@ -133,7 +162,7 @@ void mix() { } } - void actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg) + void MultirotorMixer::actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg) { // read message for(int i = 0;i < msg.NUM_ACTUATOR_CONTROLS;i++) { @@ -148,16 +177,14 @@ void mix() { for (int i = 0; i < _rotor_count; i++) { rotor_vel_msg.motor_speed.push_back(outputs.control[i]); } - pub.publish(rotor_vel_msg); + _pub.publish(rotor_vel_msg); } int main(int argc, char **argv) { ros::init(argc, argv, "mc_mixer"); - ros::NodeHandle n; - ros::Subscriber sub = n.subscribe("actuator_controls_0", 1000, actuatorControlsCallback); - ros::Publisher pub = n.advertise("mixed_motor_commands",10); + MultirotorMixer mixer; ros::spin(); From bfc398442663a943ff1e0fa21ec50b9960abb5a7 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 30 Dec 2014 11:41:28 +0100 Subject: [PATCH 4/4] cleanup --- src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp | 38 ++++++++----------- 1 file changed, 15 insertions(+), 23 deletions(-) diff --git a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp index 79eaf19e52..7092a80175 100644 --- a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp +++ b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp @@ -41,20 +41,18 @@ #include #include #include - + class MultirotorMixer { public: MultirotorMixer(); struct Rotor { - float roll_scale; - float pitch_scale; - float yaw_scale; + float roll_scale; + float pitch_scale; + float yaw_scale; + }; - }; - - void mix(); void actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg); private: @@ -62,7 +60,7 @@ private: ros::NodeHandle _n; ros::Subscriber _sub; ros::Publisher _pub; - + const Rotor *_rotors; unsigned _rotor_count; @@ -75,21 +73,18 @@ private: float control[6]; }outputs; + void mix(); - }; - - const MultirotorMixer::Rotor _config_x[] = { - { 0.000000, -1.000000, -1.00 }, - { -0.000000, 1.000000, -1.00 }, + { 0.000000, -1.000000, -1.00 }, + { -0.000000, 1.000000, -1.00 }, { 1.000000, 0.000000, 1.00 }, - { -1.000000, 0.000000, 1.00 }, + { -1.000000, 0.000000, 1.00 }, }; const MultirotorMixer::Rotor *_config_index = { &_config_x[0] - }; MultirotorMixer::MultirotorMixer(): @@ -97,10 +92,9 @@ MultirotorMixer::MultirotorMixer(): _rotors(_config_index) { _sub = _n.subscribe("actuator_controls_0", 1000, &MultirotorMixer::actuatorControlsCallback,this); - _pub = _n.advertise("mixed_motor_commands",10); + _pub = _n.advertise("mixed_motor_commands",10); } - void MultirotorMixer::mix() { float roll = math::constrain(inputs.control[0], -1.0f, 1.0f); float pitch = math::constrain(inputs.control[1], -1.0f, 1.0f); @@ -164,28 +158,26 @@ void MultirotorMixer::mix() { void MultirotorMixer::actuatorControlsCallback(const PX4_TOPIC_T(actuator_controls_0) &msg) { - // read message + // read message for(int i = 0;i < msg.NUM_ACTUATOR_CONTROLS;i++) { inputs.control[i] = msg.control[i]; } - + // mix mix(); // publish message mav_msgs::MotorSpeed rotor_vel_msg; for (int i = 0; i < _rotor_count; i++) { - rotor_vel_msg.motor_speed.push_back(outputs.control[i]); + rotor_vel_msg.motor_speed.push_back(outputs.control[i]); } _pub.publish(rotor_vel_msg); - } int main(int argc, char **argv) { ros::init(argc, argv, "mc_mixer"); - MultirotorMixer mixer; - + MultirotorMixer mixer; ros::spin(); return 0;