-
Notifications
You must be signed in to change notification settings - Fork 20.2k
Add support for MAV_CMD_DO_SET_ACTUATOR #32033
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
base: master
Are you sure you want to change the base?
Add support for MAV_CMD_DO_SET_ACTUATOR #32033
Conversation
peterbarker
left a comment
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
In its current form this is really just a normalised replacement for MAV_CMD_DO_SET_SERVO, I guess?
At the moment I think all boards are going to pay a penalty for having this feature, but only Sub firmwares will get any benefit. We should probably move the instantiation of the thing up to AP_Vehicle and have the feature off by default. Probably only need to do the latter on this PR. Also needs adding to build_options.py
| '''Send MAV_CMD_DO_SET_ACTUATOR for specified actuator (1-6) with given value''' | ||
| actuator_values = [float('nan')] * 6 | ||
| actuator_values[actuator_num - 1] = value | ||
| self.run_cmd( |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Also needs to test run_cmd_int - several places iterate to do that in the test suite
| } | ||
|
|
||
| void Actuators::set_actuator(uint8_t actuator_num, float value) { | ||
| if (actuator_num >= ACTUATOR_CHANNELS) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| if (actuator_num >= ACTUATOR_CHANNELS) { | |
| if (actuator_num >= sizeof(aux_actuator_value)) { |
| if (actuator_num >= ACTUATOR_CHANNELS) { | ||
| return; | ||
| } | ||
| aux_actuator_value[actuator_num] = constrain_float((value + 1)*0.5f, 0.0f, 1.0f); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
What's the +1 for?! Left-over from when these were integers?
| #include <AP_Param/AP_Param.h> | ||
| #include <SRV_Channel/SRV_Channel_config.h> | ||
|
|
||
| #define ACTUATOR_CHANNELS 6 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Needs a better name if it's to be in the header.
| void center_actuator(uint8_t actuator_num); | ||
| void set_actuator(uint8_t actuator_num, float value); | ||
|
|
||
| CLASS_NO_COPY(Actuators); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
By tradition put this up under the constructor
| #include <AP_Arming/AP_Arming.h> | ||
| #include <AP_Actuators/AP_Actuators_config.h> | ||
| #if AP_ACTUATORS_ENABLED | ||
| #include <AP_Actuators/actuators.h> |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| #include <AP_Actuators/actuators.h> | |
| #include <AP_Actuators/AP_Actuators.h> |
| } | ||
| return MAV_RESULT_ACCEPTED; | ||
| } | ||
| #endif |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| #endif | |
| #endif // AP_ACTUATORS_ENABLED |
| const uint8_t index = static_cast<uint8_t>(packet.z); | ||
| const uint8_t actuator_offset = index * ACTUATOR_CHANNELS; | ||
|
|
||
| for (int i = 0; i < ACTUATOR_CHANNELS; i++) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| for (int i = 0; i < ACTUATOR_CHANNELS; i++) { | |
| for (int i = 0; i < ARRAY_SIZE(actuator_values); i++) { |
| return MAV_RESULT_UNSUPPORTED; | ||
| } | ||
|
|
||
| const float actuator_values[ACTUATOR_CHANNELS] = { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I don't think there's any linkage between this and the library? i.e. this shouldn't be using ACTUATOR_CHANNELS at all.
| static_cast<float>(packet.x), | ||
| static_cast<float>(packet.y) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ummm.
We might be able to do this. But it will require people understanding we're putting a very weird number into an int32 field on the assumption that everyone knows we might be transporting NaNs in an int32 this way!
You can represent no-valid-value as INT32_MAX in these fields when transported as integers
depends on ArduPilot/mavlink#437