Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mission: Fix #19596 and MAV_CMD_DO_REPEAT_RELAY #19606

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 2 additions & 2 deletions libraries/AP_Mission/AP_Mission_Commands.cpp
Expand Up @@ -73,12 +73,12 @@ bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Com
return sre->do_repeat_servo(cmd.content.repeat_servo.channel,
cmd.content.repeat_servo.pwm,
cmd.content.repeat_servo.repeat_count,
cmd.content.repeat_servo.cycle_time * 1000.0f);
cmd.content.repeat_servo.cycle_time);

case MAV_CMD_DO_REPEAT_RELAY:
return sre->do_repeat_relay(cmd.content.repeat_relay.num,
cmd.content.repeat_relay.repeat_count,
cmd.content.repeat_relay.cycle_time * 1000.0f);
cmd.content.repeat_relay.cycle_time);
default:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("Unhandled servo/relay case");
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp
Expand Up @@ -81,7 +81,7 @@ bool AP_ServoRelayEvents::do_set_relay(uint8_t relay_num, uint8_t state)
}

bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_value,
int16_t _repeat, uint16_t _delay_ms)
int16_t _repeat, uint16_t _delay_s)
{
SRV_Channel *c = SRV_Channels::srv_channel(_channel-1);
if (c == nullptr) {
Expand All @@ -104,14 +104,14 @@ bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_valu
type = EVENT_TYPE_SERVO;

start_time_ms = 0;
delay_ms = _delay_ms / 2;
delay_ms = uint32_t(_delay_s) * 1000 / 2;
repeat = _repeat * 2;
servo_value = _servo_value;
update_events();
return true;
}

bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, uint32_t _delay_ms)
bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, uint16_t _delay_s)
{
AP_Relay *relay = AP::relay();
if (relay == nullptr) {
Expand All @@ -123,7 +123,7 @@ bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, ui
type = EVENT_TYPE_RELAY;
channel = relay_num;
start_time_ms = 0;
delay_ms = _delay_ms/2; // half cycle time
delay_ms = uint32_t(_delay_s) * 1000 / 2; // half cycle time
repeat = _repeat*2; // number of full cycles
update_events();
return true;
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h
Expand Up @@ -28,8 +28,8 @@ class AP_ServoRelayEvents {

bool do_set_servo(uint8_t channel, uint16_t pwm);
bool do_set_relay(uint8_t relay_num, uint8_t state);
bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms);
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms);
bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_s);
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint16_t period_s);
void update_events(void);

private:
Expand All @@ -48,7 +48,7 @@ class AP_ServoRelayEvents {
uint32_t start_time_ms;

// how long to delay the next firing of event in millis
uint16_t delay_ms;
uint32_t delay_ms;

// how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles
int16_t repeat;
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_ServoRelay.cpp
Expand Up @@ -19,7 +19,7 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &
break;

case MAV_CMD_DO_REPEAT_SERVO:
if (handler->do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4 * 1000)) {
if (handler->do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4)) {
result = MAV_RESULT_ACCEPTED;
}
break;
Expand All @@ -31,7 +31,7 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &
break;

case MAV_CMD_DO_REPEAT_RELAY:
if (handler->do_repeat_relay(packet.param1, packet.param2, packet.param3 * 1000)) {
if (handler->do_repeat_relay(packet.param1, packet.param2, packet.param3)) {
result = MAV_RESULT_ACCEPTED;
}
break;
Expand Down