Skip to content

Commit

Permalink
Fix bug in imet resistance model
Browse files Browse the repository at this point in the history
  • Loading branch information
tony2157 committed Jul 28, 2020
1 parent cec38bc commit 2bc433e
Showing 1 changed file with 5 additions and 4 deletions.
9 changes: 5 additions & 4 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,15 +234,16 @@ void Copter::send_cass_imet(mavlink_channel_t chan) {
if(!HAVE_PAYLOAD_SPACE(chan, CASS_SENSOR_RAW)){
return;
}
for(uint8_t i=0; i<4; i++){
raw_sensor[i] = copter.CASS_Imet[i].resistance();
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// Variables simulation for IMET resistance measurements
// Variables simulation for IMET resistance measurements
for(uint8_t i=0; i<4; i++){
raw_sensor[i] = -356.9892f*raw_sensor[i] + 110935.3763f;
}
//printf("HYT271 temp: %5.2f \n",raw_sensor[0]);
#else
for(uint8_t i=0; i<4; i++){
raw_sensor[i] = copter.CASS_Imet[i].resistance();
}
#endif
// Call Mavlink function and send CASS data
mavlink_msg_cass_sensor_raw_send(
Expand Down

0 comments on commit 2bc433e

Please sign in to comment.