MAVSDK-Python icon indicating copy to clipboard operation
MAVSDK-Python copied to clipboard

set position velocity and acceleration offboard setpoint

Open alireza787b opened this issue 2 years ago • 10 comments

Hi. As far as I see I can either send acceleration offboard or position, velocity offboard is that correct? Can we just send all? I can see that px4 supports it and we can achieve similar behavior using Mavros. I want to send offboard setpoints for position and feedforward the acceleration and velocity as well. if this function is not available, how can I implement it myself? I think we should chang ethe mavlink command that is being sent but since everything is auto-generated I don't know how and what to look for

alireza787b avatar May 16 '23 16:05 alireza787b

Yes, that's correct. The closest API for you would be position with velocity feedforward. If that's not enough, consider adding it.

First step is to add the API that you would like here: https://github.com/mavlink/MAVSDK-Proto/blob/main/protos/offboard/offboard.proto

julianoes avatar May 17 '23 02:05 julianoes

Is there documentation or explanation and example of how to add this? I don't know he concepts behind that which parts I should edit and which part is auto-generated.

alireza787b avatar May 17 '23 05:05 alireza787b

The first step is the proto file, then auto-generation happens from that in the next step.

Also see: https://mavsdk.mavlink.io/main/en/cpp/contributing/plugins.html

julianoes avatar May 18 '23 04:05 julianoes

Thanks I already read that doc and almost did all it said. I created my custom function and it should work. this is the function in cpp:

Offboard::Result OffboardImpl::send_position_velocity_acceleration_ned()
{
    // const static uint16_t IGNORE_AX = (1 << 6);
    // const static uint16_t IGNORE_AY = (1 << 7);
    // const static uint16_t IGNORE_AZ = (1 << 8);
    const static uint16_t IGNORE_YAW_RATE = (1 << 11);

    const auto position_and_velocity = [this]() {
        std::lock_guard<std::mutex> lock(_mutex);
        return std::make_pair<>(_position_ned_yaw, _velocity_ned_yaw);
    }();

    const auto acceleration_ned = [this]() {
        std::lock_guard<std::mutex> lock(_mutex);
        return _acceleration_ned;
    }();

    mavlink_message_t message;
    mavlink_msg_set_position_target_local_ned_pack(
        _system_impl->get_own_system_id(),
        _system_impl->get_own_component_id(),
        &message,
        static_cast<uint32_t>(_system_impl->get_time().elapsed_ms()),
        _system_impl->get_system_id(),
        _system_impl->get_autopilot_id(),
        MAV_FRAME_LOCAL_NED,
        IGNORE_YAW_RATE,
        position_and_velocity.first.north_m,
        position_and_velocity.first.east_m,
        position_and_velocity.first.down_m,
        position_and_velocity.second.north_m_s,
        position_and_velocity.second.east_m_s,
        position_and_velocity.second.down_m_s,
        acceleration_ned.north_m_s2,
        acceleration_ned.east_m_s2,
        acceleration_ned.down_m_s2,
        to_rad_from_deg(position_and_velocity.first.yaw_deg), // yaw
        0.0f); // yaw_rate
    return _system_impl->send_message(message) ? Offboard::Result::Success :
                                                 Offboard::Result::ConnectionError;
}
Offboard::Result OffboardImpl::set_position_velocity_acceleration_ned(
    Offboard::PositionNedYaw position_ned_yaw, Offboard::VelocityNedYaw velocity_ned_yaw, Offboard::AccelerationNed acceleration_ned)
{
    {
        std::lock_guard<std::mutex> lock(_mutex);
        _position_ned_yaw = position_ned_yaw;
        _velocity_ned_yaw = velocity_ned_yaw;
        _acceleration_ned = acceleration_ned;

        if (_mode != Mode::PositionVelocityAccelerationNed) {
            if (_call_every_cookie) {
                // If we're already sending other setpoints, stop that now.
                _system_impl->remove_call_every(_call_every_cookie);
                _call_every_cookie = nullptr;
            }
            // We automatically send Ned setpoints from now on.
            _system_impl->add_call_every(
                [this]() { send_position_velocity_acceleration_ned(); }, SEND_INTERVAL_S, &_call_every_cookie);

            _mode = Mode::PositionVelocityAccelerationNed;
        } else {
            // We're already sending these kind of setpoints. Since the setpoint change, let's
            // reschedule the next call, so we don't send setpoints too often.
            _system_impl->reset_call_every(_call_every_cookie);
        }
    }

    // also send it right now to reduce latency
    return send_position_velocity_acceleration_ned();
}

and this is in .h

 mutable std::mutex _mutex{};
    enum class Mode {
        NotActive,
        PositionNed,
        // PositionGlobalAMSL,
        PositionGlobalAltRel,
        VelocityNed,
        PositionVelocityNed,
        PositionVelocityAccelerationNed,
        AccelerationNed,
        VelocityBody,
        Attitude,
        AttitudeRate,
        ActuatorControl
    } _mode = Mode::NotActive;

Offboard::Result send_position_velocity_acceleration_ned();

 Offboard::Result set_position_velocity_acceleration_ned(
        Offboard::PositionNedYaw position_ned_yaw, Offboard::VelocityNedYaw velocity_ned_yaw, Offboard::AccelerationNed acceleration_ned);

but when I try to build it in the last step in 100% I get the following error:

[100%] Building CXX object src/mavsdk_server/test/CMakeFiles/unit_tests_mavsdk_server.dir/offboard_service_impl_test.cpp.o In file included from /home/alireza/MAVSDK/src/mavsdk_server/test/offboard_service_impl_test.cpp:5: /home/alireza/MAVSDK/src/mavsdk_server/test/../src/plugins/offboard/offboard_service_impl.h: In instantiation of ‘grpc::Status mavsdk::mavsdk_server::OffboardServiceImpl<Offboard, LazyPlugin>::SetPositionVelocityAccelerationNed(grpc::ServerContext*, const mavsdk::rpc::offboard::SetPositionVelocityAccelerationNedRequest*, mavsdk::rpc::offboard::SetPositionVelocityAccelerationNedResponse*) [with Offboard = testing::NiceMockmavsdk::testing::MockOffboard; LazyPlugin = testing::NiceMock<mavsdk::mavsdk_server::testing::MockLazyPlugin<testing::NiceMockmavsdk::testing::MockOffboard > >]’: /home/alireza/MAVSDK/src/mavsdk_server/test/../src/plugins/offboard/offboard_service_impl.h:959:18: required from here /home/alireza/MAVSDK/src/mavsdk_server/test/../src/plugins/offboard/offboard_service_impl.h:984:52: error: ‘class testing::NiceMockmavsdk::testing::MockOffboard’ has no member named ‘set_position_velocity_acceleration_ned’; did you mean ‘set_position_velocity_ned’? 984 | auto result = _lazy_plugin.maybe_plugin()->set_position_velocity_acceleration_ned(translateFromRpcPositionNedYaw(request->position_ned_yaw()), translateFromRpcVelocityNedYaw(request->velocity_ned_yaw()), translateFromRpcAccelerationNed(request->acceleration_ned())); | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ | set_position_velocity_ned cc1plus: note: unrecognized command-line option ‘-Wno-unknown-warning-option’ may have been intended to silence earlier diagnostics gmake[2]: *** [src/mavsdk_server/test/CMakeFiles/unit_tests_mavsdk_server.dir/build.make:160: src/mavsdk_server/test/CMakeFiles/unit_tests_mavsdk_server.dir/offboard_service_impl_test.cpp.o] Error 1 gmake[1]: *** [CMakeFiles/Makefile2:2175: src

Should I do extra step in mavsdk_server files? I think I can hard code the position_velocity to include ACC as well and it should work but I am planing to create a new function and then pull it to repo so others can use it later

alireza787b avatar May 18 '23 05:05 alireza787b

Can you make the PR for the proto changes, so that I can review those first?

For the mock errors, make sure to add the API here: https://github.com/mavlink/MAVSDK/blob/main/src/mavsdk/plugins/offboard/mocks/offboard_mock.h

julianoes avatar May 18 '23 05:05 julianoes

editing the mock file was the step missing in the docs and it solved it. it is now generated in mavsdk cpp. now I want to generate it for python as well. this is what I don't know how yet. My forked mavsdk repo is at : https://github.com/alireza787b/MAVSDK

Would you like me to send PR on mavsdk or mavsdk python? I need help with this converting to Python part. I haven't found any documentation on that.

alireza787b avatar May 18 '23 07:05 alireza787b

Would you like me to send PR on mavsdk or mavsdk python?

First one would be MAVSDK-Proto. That will generate the C++ headers, which you need to implement. Python is then fully generated.

JonasVautherin avatar May 18 '23 08:05 JonasVautherin

I managed to genreate python and it shows up but when I run the new function in python I get multithreading or sth like that . I created a pull request on mavsdk proto and describe the steps I did and the problem this is the link: https://github.com/mavlink/MAVSDK-Proto/pull/314

PS: sth is still unclear for me. I edited the cpp sources in mavsdk repo. how they end up effecting the python? how the system exactly works? I changed the proto, build the mavsdk and then did python generation from mavsdk python.

Thanks for your help

alireza787b avatar May 19 '23 05:05 alireza787b

Hello! You are correct that in offboard mode, you can send either acceleration or position/velocity setpoints. However, it is indeed possible to send all three types of setpoints simultaneously if desired. PX4 and Mavros support this capability, allowing you to achieve the desired behavior.

If the function for sending offboard setpoints with position, velocity, and acceleration is not readily available, you can implement it yourself. One way to do this is by modifying the Mavlink command that is being sent. Since the code is auto-generated, you might need to search for the specific location where the setpoint commands are handled.

Start by locating the part of the code where Mavlink messages are generated and sent to the flight controller. Look for functions or sections related to offboard setpoints, such as set_position_target_local_ned or set_position_target_global_int. These functions typically handle position and velocity setpoints.

To include acceleration in your setpoint message, you would need to modify the existing Mavlink message structure and include the appropriate acceleration fields. You may need to refer to the Mavlink message definitions to ensure compatibility.

Once you have made the necessary changes to include acceleration in the setpoint message, rebuild or recompile the code, and deploy it to your system. Make sure to test thoroughly to ensure the desired behavior is achieved.

Remember to consult the PX4 and Mavros documentation and community forums for further guidance and support during the implementation process. Good luck!

naturalspirit299 avatar Jul 15 '23 09:07 naturalspirit299

Hello! You are correct that in offboard mode, you can send either acceleration or position/velocity setpoints. However, it is indeed possible to send all three types of setpoints simultaneously if desired. PX4 and Mavros support this capability, allowing you to achieve the desired behavior.

If the function for sending offboard setpoints with position, velocity, and acceleration is not readily available, you can implement it yourself. One way to do this is by modifying the Mavlink command that is being sent. Since the code is auto-generated, you might need to search for the specific location where the setpoint commands are handled.

Start by locating the part of the code where Mavlink messages are generated and sent to the flight controller. Look for functions or sections related to offboard setpoints, such as set_position_target_local_ned or set_position_target_global_int. These functions typically handle position and velocity setpoints.

To include acceleration in your setpoint message, you would need to modify the existing Mavlink message structure and include the appropriate acceleration fields. You may need to refer to the Mavlink message definitions to ensure compatibility.

Once you have made the necessary changes to include acceleration in the setpoint message, rebuild or recompile the code, and deploy it to your system. Make sure to test thoroughly to ensure the desired behavior is achieved.

Remember to consult the PX4 and Mavros documentation and community forums for further guidance and support during the implementation process. Good luck!

Thanks for the information and guide I did that and added a new function for setting all position, velocity, and acceleration with command and it works ok the link to the pull request is : https://github.com/mavlink/MAVSDK/pull/2057

and in it available in the latest mavsdk release

alireza787b avatar Jul 16 '23 02:07 alireza787b