What are the different of Offboard and Action of set_position_xx and set_actuator_xx?
The Action have API:
goto_location (double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg)const
And Offboard have API:
set_position_global(PositionGlobalYaw position_global_yaw) const;
The Action have API:
set_actuator (int32_t index, float value)const
And Offboard have API:
set_actuator_control(ActuatorControl actuator_control) const;
What are the different of them??
And, is there a way to directly ctrl the ch out? For the situation of no position info(No gps .etc), just like using a hand hold "Remote control"!! Or there is a way to orerride the "RCin" like the node "rc/override" in mavros!!!
And, calling ManualControl::start_position_control() in my ardupilot rover SITL, it print err:
[04:34:42|Error] Cannot translate flight mode to ArduPilot Rover mode. (system_impl.cpp:925)
and change to ardupilot ArduCopter, its not print err
And this ManualControl::start_position_control() says its need position info such as GPS fixed, so what is the way to simu "using a hand hold "Remote control"!!"...
goto_location
This sends a command (which is acked), so it's for one off / slow (max around 1 Hz) setpoints. For PX4 this uses the existing smoothing, etc. like in any auto/mission mode. For ArduPilot, I'm not too sure.
set_position_global
This uses what is called OFFBOARD mode in PX4 and GUIDED in ArduPilot. You typically send this message at a rate faster than 2 Hz and continuously update/send it. For PX4, this does not do any smoothing but is more direct input.
set_actuator
This is for one off commands to e.g. move a servo to do a specific action. It's not meant for smooth operation.
set_actuator_control
This one is again using OFFBOARD/GUIDED mode and for smooth control. However, it is not supported by PX4 in later versions (I think since around 1.14). For ArduPilot, I'm not sure, you'd have to try it.
And, calling ManualControl::start_position_control() in my ardupilot rover SITL, it print err: [04:34:42|Error] Cannot translate flight mode to ArduPilot Rover mode. (system_impl.cpp:925)
I'm not sure what to say here. MAVSDK is not really tested with ArduRover. It sounds like the offboard mode that MAVSDK tries to use isn't supported in ArduRover. I'd need to learn from someone that knows ArduRover, how this is supposed to work.
And this ManualControl::start_position_control() says its need position info such as GPS fixed, so what is the way to simu "using a hand hold "Remote control"!!"...
For just hand control, you should look into the ManualControl plugin.
OK, OK What I need is to directly ctrl the ch out, For the situation of no position info(No gps .etc), just like using a hand hold "Remote control"!! After some search, find that just need watch the RC out and orerride RC in, I can using MavlinkDirect to send mavlink msg ID SERVO_OUTPUT_RAW and RC_CHANNELS_OVERRIDE to realize these.
And the ManualControl::start_position_control() in my ardupilot rover SITL print err issue, Its maybe just the src code limit And I find that in ManualControlImpl:
_system_impl->set_flight_mode_async(
FlightMode::Posctl, [this, callback](MavlinkCommandSender::Result result, float) {
command_result_callback(result, callback);
});
the input mode is FlightMode::Posctl, so in ardupiot rover its not pass:
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
{
switch (flight_mode) {
case FlightMode::Mission:
return ardupilot::RoverMode::Auto;
...
case FlightMode::Unknown:
...
case FlightMode::Posctl: // ———————————— here
...
default:
return ardupilot::RoverMode::Unknown;
}
}
If I can using MavlinkDirect to send mavlink msg ID SERVO_OUTPUT_RAW and RC_CHANNELS_OVERRIDE to realize watch the RC out and orerride RC in, and if this is what you recommend to do so, then this issue and https://github.com/mavlink/MAVSDK/issues/2697 can be close
Can't you just use some manual mode for when you don't have GPS?
I am using RC_CHANNELS_OVERRIDE just in manual mode.
By the way:
Can Mavsdk specify a thread, or is there a handle() function to handle everything, so that when using it, the execution context inside the callback function is the same as the context where the handle() function resides, thus eliminating the need for locking when reading and writing my variables inside the callback fun?
I am using RC_CHANNELS_OVERRIDE just in manual mode.
And that's not working? I'm confused.
Can Mavsdk specify a thread, or is there a handle() function to handle everything, so that when using it, the execution context inside the callback function is the same as the context where the handle() function resides, thus eliminating the need for locking when reading and writing my variables inside the callback fun?
Nope, not sure how that is generally done. Can you point me to other libraries or resources as an explainer?
I am using RC_CHANNELS_OVERRIDE just in manual mode.
Tested, working. And this is also what the mavros rc/orerride node does.
Can Mavsdk specify a thread, or is there a handle() function to handle everything, so that when using it, the execution context inside the callback function is the same as the context where the handle() function resides, thus eliminating the need for locking when reading and writing my variables inside the callback fun?
I feel this is a common practice. Such as libuv、libhv、lvgl libs
Ok, I read more about it. I think we can easily add support for it, because all user callbacks are already queued on a separate callback thread.
Which API do you prefer:
A: poll:
// User's code
while (running) {
mavsdk.poll(); // Runs pending callbacks on THIS thread
// or poll_one() to run just one callback
do_other_stuff();
}
B: executor
mavsdk.set_callback_executor([](std::function<void()> fn) {
my_event_loop.post(fn); // e.g., Qt's QMetaObject::invokeMethod, Asio's post(), etc.
});
I'm slightly leaning towards B.
I think both are needed for diffteren type users. But B seems a little heavy for many fun calls. I prefer A 👍