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

ACTUATOR_OUTPUT_STATUS MAVLink stream for ESCs #13145

Closed
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
77 changes: 76 additions & 1 deletion src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@
#include <uORB/topics/sensor_mag.h>
#include <uORB/topics/vehicle_air_data.h>
#include <uORB/topics/vehicle_magnetometer.h>
#include <uORB/topics/esc_status.h>
#include <uORB/uORB.h>

using matrix::wrap_2pi;
Expand Down Expand Up @@ -5024,6 +5025,79 @@ class MavlinkStreamObstacleDistance : public MavlinkStream
}
};

class MavlinkStreamActuatorOutputStatus : public MavlinkStream
{
public:
const char *get_name() const
{
return MavlinkStreamActuatorOutputStatus::get_name_static();
}

static const char *get_name_static()
{
return "ACTUATOR_OUTPUT_STATUS";
}

static uint16_t get_id_static()
{
return MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS;
}

uint16_t get_id()
{
return get_id_static();
}

static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamActuatorOutputStatus(mavlink);
}

unsigned get_size()
{
return _esc_status_sub->is_published() ? (MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) :
0;
}

private:
uint64_t _esc_status_time;

MavlinkOrbSubscription *_esc_status_sub;

/* do not allow top copying this class */
MavlinkStreamActuatorOutputStatus(MavlinkStreamActuatorOutputStatus &) = delete;
MavlinkStreamActuatorOutputStatus &operator = (const MavlinkStreamActuatorOutputStatus &) = delete;

protected:
explicit MavlinkStreamActuatorOutputStatus(Mavlink *mavlink) : MavlinkStream(mavlink),
_esc_status_time(0),
_esc_status_sub(_mavlink->add_orb_subscription(ORB_ID(esc_status)))
{
}

bool send(const hrt_abstime t)
{
esc_status_s esc_status;

if (_esc_status_sub->update(&_esc_status_time, &esc_status)) {
mavlink_actuator_output_status_t msg = {};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@hamishwillee Is that message supposed to contain the feedback from the actuators? It's not clear to me from the message spec.

Copy link
Contributor Author

@irsdkv irsdkv Oct 10, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

IMO ACTUATOR_OUTPUT_STATUS message should provide feedback from the actuators because of we can receive controls with ACTUATOR_CONTROL_TARGET message.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bkueng It is the updated version of SERVO_OUTPUT_RAW. Discussed in mavlink/mavlink#926

So my understanding is that this is just the raw PWM values we are outputing on all MAIN, AUX, whatever. Not feedback from actuator.

Can you review that chain and confirm you agree. If so, I will add note to it saying this.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That was my understanding as well.
However that means the implementation here is not correct.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@irsdkv ACTUATOR_CONTROL_TARGET contains the values before the mixing.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bkueng Cool, Assigned you clarification for review: mavlink/mavlink#1252

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bkueng so is this PR now correct or not? I'm confused.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bkueng so is this PR now correct or not? I'm confused.

It's not. I thought I wrote that?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@irsdkv have you fixed the issue raised here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@julianoes I'm still confused.
What I should fix?


msg.time_usec = hrt_absolute_time();
msg.active = esc_status.esc_count;

for (unsigned i = 0; i < esc_status.esc_count; i++) {
msg.actuator[i] = static_cast<float>(esc_status.esc[i].esc_rpm);
}

mavlink_msg_actuator_output_status_send_struct(_mavlink->get_channel(), &msg);

return true;
}

return false;
}
};

static const StreamListItem streams_list[] = {
StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static, &MavlinkStreamHeartbeat::get_id_static),
StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static, &MavlinkStreamStatustext::get_id_static),
Expand Down Expand Up @@ -5083,7 +5157,8 @@ static const StreamListItem streams_list[] = {
StreamListItem(&MavlinkStreamGroundTruth::new_instance, &MavlinkStreamGroundTruth::get_name_static, &MavlinkStreamGroundTruth::get_id_static),
StreamListItem(&MavlinkStreamPing::new_instance, &MavlinkStreamPing::get_name_static, &MavlinkStreamPing::get_id_static),
StreamListItem(&MavlinkStreamOrbitStatus::new_instance, &MavlinkStreamOrbitStatus::get_name_static, &MavlinkStreamOrbitStatus::get_id_static),
StreamListItem(&MavlinkStreamObstacleDistance::new_instance, &MavlinkStreamObstacleDistance::get_name_static, &MavlinkStreamObstacleDistance::get_id_static)
StreamListItem(&MavlinkStreamObstacleDistance::new_instance, &MavlinkStreamObstacleDistance::get_name_static, &MavlinkStreamObstacleDistance::get_id_static),
StreamListItem(&MavlinkStreamActuatorOutputStatus::new_instance, &MavlinkStreamActuatorOutputStatus::get_name_static, &MavlinkStreamActuatorOutputStatus::get_id_static)
};

const char *get_stream_name(const uint16_t msg_id)
Expand Down