Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
A
ardupilot
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
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
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
SASC
ardupilot
Commits
ddc70058
Commit
ddc70058
authored
8 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Rover: reporting wheel encoder rpm
parent
ae487aa9
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
APMrover2/GCS_Mavlink.cpp
+14
-1
14 additions, 1 deletion
APMrover2/GCS_Mavlink.cpp
APMrover2/Rover.h
+2
-0
2 additions, 0 deletions
APMrover2/Rover.h
APMrover2/sensors.cpp
+8
-0
8 additions, 0 deletions
APMrover2/sensors.cpp
with
24 additions
and
1 deletion
APMrover2/GCS_Mavlink.cpp
+
14
−
1
View file @
ddc70058
...
@@ -269,6 +269,14 @@ void Rover::send_current_waypoint(mavlink_channel_t chan)
...
@@ -269,6 +269,14 @@ void Rover::send_current_waypoint(mavlink_channel_t chan)
mavlink_msg_mission_current_send
(
chan
,
mission
.
get_current_nav_index
());
mavlink_msg_mission_current_send
(
chan
,
mission
.
get_current_nav_index
());
}
}
void
Rover
::
send_wheel_encoder
(
mavlink_channel_t
chan
)
{
// send wheel encoder data using rpm message
if
(
g2
.
wheel_encoder
.
enabled
(
0
)
||
g2
.
wheel_encoder
.
enabled
(
1
))
{
mavlink_msg_rpm_send
(
chan
,
wheel_encoder_rpm
[
0
],
wheel_encoder_rpm
[
1
]);
}
}
uint8_t
GCS_MAVLINK_Rover
::
sysid_my_gcs
()
const
uint8_t
GCS_MAVLINK_Rover
::
sysid_my_gcs
()
const
{
{
return
rover
.
g
.
sysid_my_gcs
;
return
rover
.
g
.
sysid_my_gcs
;
...
@@ -415,6 +423,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
...
@@ -415,6 +423,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
send_distance_sensor
(
rover
.
rangefinder
);
send_distance_sensor
(
rover
.
rangefinder
);
break
;
break
;
case
MSG_RPM
:
CHECK_PAYLOAD_SIZE
(
RPM
);
rover
.
send_wheel_encoder
(
chan
);
break
;
case
MSG_MOUNT_STATUS
:
case
MSG_MOUNT_STATUS
:
#if MOUNT == ENABLED
#if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE
(
MOUNT_STATUS
);
CHECK_PAYLOAD_SIZE
(
MOUNT_STATUS
);
...
@@ -481,7 +494,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
...
@@ -481,7 +494,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
case
MSG_TERRAIN
:
case
MSG_TERRAIN
:
case
MSG_OPTICAL_FLOW
:
case
MSG_OPTICAL_FLOW
:
case
MSG_GIMBAL_REPORT
:
case
MSG_GIMBAL_REPORT
:
case
MSG_RPM
:
case
MSG_POSITION_TARGET_GLOBAL_INT
:
case
MSG_POSITION_TARGET_GLOBAL_INT
:
case
MSG_LANDING
:
case
MSG_LANDING
:
break
;
// just here to prevent a warning
break
;
// just here to prevent a warning
...
@@ -691,6 +703,7 @@ GCS_MAVLINK_Rover::data_stream_send(void)
...
@@ -691,6 +703,7 @@ GCS_MAVLINK_Rover::data_stream_send(void)
send_message
(
MSG_MOUNT_STATUS
);
send_message
(
MSG_MOUNT_STATUS
);
send_message
(
MSG_EKF_STATUS_REPORT
);
send_message
(
MSG_EKF_STATUS_REPORT
);
send_message
(
MSG_VIBRATION
);
send_message
(
MSG_VIBRATION
);
send_message
(
MSG_RPM
);
}
}
}
}
...
...
This diff is collapsed.
Click to expand it.
APMrover2/Rover.h
+
2
−
0
View file @
ddc70058
...
@@ -415,6 +415,7 @@ private:
...
@@ -415,6 +415,7 @@ private:
float
wheel_encoder_last_angle_rad
[
WHEELENCODER_MAX_INSTANCES
];
// distance in radians at time of last update to EKF
float
wheel_encoder_last_angle_rad
[
WHEELENCODER_MAX_INSTANCES
];
// distance in radians at time of last update to EKF
uint32_t
wheel_encoder_last_update_ms
[
WHEELENCODER_MAX_INSTANCES
];
// system time of last ping from each encoder
uint32_t
wheel_encoder_last_update_ms
[
WHEELENCODER_MAX_INSTANCES
];
// system time of last ping from each encoder
uint32_t
wheel_encoder_last_ekf_update_ms
;
// system time of last encoder data push to EKF
uint32_t
wheel_encoder_last_ekf_update_ms
;
// system time of last encoder data push to EKF
float
wheel_encoder_rpm
[
WHEELENCODER_MAX_INSTANCES
];
// for reporting to GCS
// True when we are doing motor test
// True when we are doing motor test
bool
motor_test
;
bool
motor_test
;
...
@@ -460,6 +461,7 @@ private:
...
@@ -460,6 +461,7 @@ private:
void
send_pid_tuning
(
mavlink_channel_t
chan
);
void
send_pid_tuning
(
mavlink_channel_t
chan
);
void
send_rangefinder
(
mavlink_channel_t
chan
);
void
send_rangefinder
(
mavlink_channel_t
chan
);
void
send_current_waypoint
(
mavlink_channel_t
chan
);
void
send_current_waypoint
(
mavlink_channel_t
chan
);
void
send_wheel_encoder
(
mavlink_channel_t
chan
);
void
gcs_data_stream_send
(
void
);
void
gcs_data_stream_send
(
void
);
void
gcs_update
(
void
);
void
gcs_update
(
void
);
void
gcs_retry_deferred
(
void
);
void
gcs_retry_deferred
(
void
);
...
...
This diff is collapsed.
Click to expand it.
APMrover2/sensors.cpp
+
8
−
0
View file @
ddc70058
...
@@ -148,6 +148,14 @@ void Rover::update_wheel_encoder()
...
@@ -148,6 +148,14 @@ void Rover::update_wheel_encoder()
* posOffset is the XYZ body frame position of the wheel hub (m)
* posOffset is the XYZ body frame position of the wheel hub (m)
*/
*/
EKF3
.
writeWheelOdom
(
delta_angle
,
delta_time
,
wheel_encoder_last_update_ms
[
i
],
g2
.
wheel_encoder
.
get_position
(
i
),
g2
.
wheel_encoder
.
get_wheel_radius
(
i
));
EKF3
.
writeWheelOdom
(
delta_angle
,
delta_time
,
wheel_encoder_last_update_ms
[
i
],
g2
.
wheel_encoder
.
get_position
(
i
),
g2
.
wheel_encoder
.
get_wheel_radius
(
i
));
// calculate rpm for reporting to GCS
if
(
is_positive
(
delta_time
))
{
wheel_encoder_rpm
[
i
]
=
(
delta_angle
/
M_2PI
)
/
(
delta_time
/
60.0
f
);
}
else
{
wheel_encoder_rpm
[
i
]
=
0.0
f
;
}
}
}
// record system time update for next iteration
// record system time update for next iteration
...
...
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