Skip to content

Commit

Permalink
AP_DDS client astyled
Browse files Browse the repository at this point in the history
  • Loading branch information
= committed Sep 18, 2024
1 parent 215d898 commit d0ff955
Showing 1 changed file with 14 additions and 10 deletions.
24 changes: 14 additions & 10 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -555,25 +555,29 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin
}

if (rx_joy_topic.axes_size >= 4) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received sensor_msgs/Joy: %f, %f, %f, %f",
msg_prefix, rx_joy_topic.axes[0], rx_joy_topic.axes[1], rx_joy_topic.axes[2], rx_joy_topic.axes[3]);
const uint32_t tnow = AP_HAL::millis();
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received %d sensor_msgs/Joy: %f, %f, %f, %f",
msg_prefix, x_joy_topic.axes_size, rx_joy_topic.axes[0],
rx_joy_topic.axes[1], rx_joy_topic.axes[2], rx_joy_topic.axes[3]);
if (rx_joy_topic.axes_size > 8U) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s Only first 8 Joy Axes will be processed.", msg_prefix);
}
const uint32_t t_now = AP_HAL::millis();

for (uint8_t i = 0; i < MIN(8U, rx_joy_topic.axes_size); i++) {

// Per MAVLink spec a value of UINT16_MAX means to ignore this field.
// Set a value of 0 to release the channel override.
if (static_cast<uint16_t>(rx_joy_topic.axes[i])!= UINT16_MAX) {
const uint16_t mapped_data = static_cast<uint16_t>(
linear_interpolate(rc().channel(i)->get_radio_min(),
rc().channel(i)->get_radio_max(),
rx_joy_topic.axes[i],
-1.0, 1.0));
RC_Channels::set_override(i, mapped_data, tnow);
linear_interpolate(rc().channel(i)->get_radio_min(),
rc().channel(i)->get_radio_max(),
rx_joy_topic.axes[i],
-1.0, 1.0));
RC_Channels::set_override(i, mapped_data, t_now);
}
}

} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received sensor_msgs/Joy. Axes size must be >= 4", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s Received sensor_msgs/Joy. Axes size must be >= 4", msg_prefix);
}
break;
}
Expand Down

0 comments on commit d0ff955

Please sign in to comment.