Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
Firmware
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alberto Ruiz Garcia
Firmware
Commits
664a2407
Commit
664a2407
authored
10 years ago
by
Thomas Gubler
Browse files
Options
Downloads
Plain Diff
Merge pull request #5 from thomasgubler/PR_mixer
Pr mixer
parents
502952e0
4307b48c
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
CMakeLists.txt
+9
-0
9 additions, 0 deletions
CMakeLists.txt
src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp
+184
-0
184 additions, 0 deletions
src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp
with
193 additions
and
0 deletions
CMakeLists.txt
+
9
−
0
View file @
664a2407
...
...
@@ -194,6 +194,15 @@ target_link_libraries(manual_input
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 ##
...
...
This diff is collapsed.
Click to expand it.
src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp
0 → 100644
+
184
−
0
View file @
664a2407
/****************************************************************************
*
* 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 mc_mixer.cpp
* Dummy multicopter mixer for euroc simulator (gazebo)
*
* @author Roman Bapst <romanbapst@yahoo.de>
*/
#include
<ros/ros.h>
#include
<px4.h>
#include
<lib/mathlib/mathlib.h>
#include
<mav_msgs/MotorSpeed.h>
class
MultirotorMixer
{
public:
MultirotorMixer
();
struct
Rotor
{
float
roll_scale
;
float
pitch_scale
;
float
yaw_scale
;
};
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
[
6
];
}
outputs
;
void
mix
();
};
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
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
<
mav_msgs
::
MotorSpeed
>
(
"mixed_motor_commands"
,
10
);
}
void
MultirotorMixer
::
mix
()
{
float
roll
=
math
::
constrain
(
inputs
.
control
[
0
],
-
1.0
f
,
1.0
f
);
float
pitch
=
math
::
constrain
(
inputs
.
control
[
1
],
-
1.0
f
,
1.0
f
);
float
yaw
=
math
::
constrain
(
inputs
.
control
[
2
],
-
1.0
f
,
1.0
f
);
float
thrust
=
math
::
constrain
(
inputs
.
control
[
3
],
0.0
f
,
1.0
f
);
float
min_out
=
0.0
f
;
float
max_out
=
0.0
f
;
/* 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.0
f
&&
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.0
f
)
{
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.0
f
)
{
scale_out
=
1.0
f
/
max_out
;
}
else
{
scale_out
=
1.0
f
;
}
/* 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.0
f
,
1.0
f
);
}
}
void
MultirotorMixer
::
actuatorControlsCallback
(
const
PX4_TOPIC_T
(
actuator_controls_0
)
&
msg
)
{
// 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
]);
}
_pub
.
publish
(
rotor_vel_msg
);
}
int
main
(
int
argc
,
char
**
argv
)
{
ros
::
init
(
argc
,
argv
,
"mc_mixer"
);
MultirotorMixer
mixer
;
ros
::
spin
();
return
0
;
}
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment