Mavlink Log frequencies and

Hello,

I am looking to change the frequencies of mavlink log messages for a higher sampling rate and add or delete some logs I need or not.

Message like this one ( line 1436 in libraries/GCS_Mavlink/GCS_common.cpp):

void GCS_MAVLINK::send_local_position(const AP_AHRS &ahrs) const
{
    Vector3f local_position, velocity;
    if (!ahrs.get_relative_position_NED_home(local_position) ||
        !ahrs.get_velocity_NED(velocity)) {
        // we don't know the position and velocity
        return;
    }

    mavlink_msg_local_position_ned_send(
        chan,
        AP_HAL::millis(),
        local_position.x,
        local_position.y,
        local_position.z,
        velocity.x,
        velocity.y,
        velocity.z);
}

are sampled at 5Hz but I can’t find where they are called. I know they are defined in library/GCS_Mavlink/GCS_common.cpp and that they seem to be called in Ardusub/GCS_mavlink.cpp with this kind of call:

bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
{   
...
case MSG_LOCAL_POSITION:
        CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
        send_local_position(sub.EKF2);
        break;
...

but I can’t identify where the logging is eventually called and where I can find the messages and the parameters (like the sampling rate) I would like to change.

Thank you in advance for your help.

Take a look at the SRn parameters where n is the serial port. Pixhawk usb is serial port 0.

Regarding the source code, data_stream_send is called by the scheduler, and the message is actually sent according to the SRn parameters.

You can also use the REQUEST_DATA_STREAM command using the MAV_DATA_STREAM enum, but this is just another way of setting the SRn parameters. Be careful playing with these things while using MAVProxy, mavproxy periodically requests a certain streamrate for all streams. Using mavproxy, you can change the streamrate of all streams with the command set streamrate 10 (10Hz). The maximum rate for any stream is 50Hz.

Thank you for your answer.

So if I understood well, the gcs_data_stream_send is called at 50Hz but from the SRn parameters, we can only call the logs from 0 to 10 Hz. And this data_stream is not only used for logging but also send data to the ground station.
Can’t I shutdown the gcs_data_stream all together and call directly logging method in a custom loop in the Sub.cpp file as

void Sub::custom_hz_logging_loop() {
GCS_MAVLINK::send_local_position(ahrs)
//... and other code
}

then in the scheduler:

SCHED_TASK(custom_hz_logging_loop, 100, ...),

or it will break ardusub ?

I think you are confusing logging and telemetry. Telemetry is the information that the autopilot sends to an external system (a ground control station like mavproxy or qgroundcontrol). Telemetry is done by the GCS class, and the *_send methods. The stream rates control the telemetry frequency, and can go up to 50Hz

Logging is writing data to the autopilot SD card. Logging is done at full main loop rate of 400Hz for some items. These functions are in logging.cpp.

Telemetry uses the MAVLink protocol, the logging format is not documented (except in source code), and it has no relationship with MAVLink.

Your example is ok except for this confusion. You will be sending a message at 100Hz, but you wont be logging it to the autopilot sd card.