Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
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
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
a83a4768
Commit
a83a4768
authored
10 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Copter: remove get_angle_targets_for_reporting fn
this saves a tiny amount of time by removing the memory copy of a Vector3f
parent
f6e12bda
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
ArduCopter/GCS_Mavlink.pde
+1
-2
1 addition, 2 deletions
ArduCopter/GCS_Mavlink.pde
ArduCopter/Log.pde
+1
-2
1 addition, 2 deletions
ArduCopter/Log.pde
ArduCopter/flight_mode.pde
+0
-5
0 additions, 5 deletions
ArduCopter/flight_mode.pde
with
2 additions
and
9 deletions
ArduCopter/GCS_Mavlink.pde
+
1
−
2
View file @
a83a4768
...
@@ -276,8 +276,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
...
@@ -276,8 +276,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
static
void
NOINLINE
send_nav_controller_output
(
mavlink_channel_t
chan
)
static
void
NOINLINE
send_nav_controller_output
(
mavlink_channel_t
chan
)
{
{
Vector3f
targets
;
const
Vector3f
&
targets
=
attitude_control
.
angle_ef_targets
();
get_angle_targets_for_reporting
(
targets
);
mavlink_msg_nav_controller_output_send
(
mavlink_msg_nav_controller_output_send
(
chan
,
chan
,
targets
.
x
/
1.0e2
f
,
targets
.
x
/
1.0e2
f
,
...
...
This diff is collapsed.
Click to expand it.
ArduCopter/Log.pde
+
1
−
2
View file @
a83a4768
...
@@ -469,8 +469,7 @@ struct PACKED log_Attitude {
...
@@ -469,8 +469,7 @@ struct PACKED log_Attitude {
// Write an attitude packet
// Write an attitude packet
static
void
Log_Write_Attitude
()
static
void
Log_Write_Attitude
()
{
{
Vector3f
targets
;
const
Vector3f
&
targets
=
attitude_control
.
angle_ef_targets
();
get_angle_targets_for_reporting
(
targets
);
struct
log_Attitude
pkt
=
{
struct
log_Attitude
pkt
=
{
LOG_PACKET_HEADER_INIT
(
LOG_ATTITUDE_MSG
),
LOG_PACKET_HEADER_INIT
(
LOG_ATTITUDE_MSG
),
time_ms
:
hal
.
scheduler
->
millis
(),
time_ms
:
hal
.
scheduler
->
millis
(),
...
...
This diff is collapsed.
Click to expand it.
ArduCopter/flight_mode.pde
+
0
−
5
View file @
a83a4768
...
@@ -327,8 +327,3 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
...
@@ -327,8 +327,3 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
}
}
}
}
// get_angle_targets_for_reporting() - returns 3d vector of roll, pitch and yaw target angles for logging and reporting to GCS
static
void
get_angle_targets_for_reporting
(
Vector3f
&
targets
)
{
targets
=
attitude_control
.
angle_ef_targets
();
}
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