forked from Archive/PX4-Autopilot
mavlink_shell: set target system and component id
These got added in https://github.com/mavlink/mavlink/pull/1725 and need to be set for correct routing.
This commit is contained in:
parent
dea404a9a3
commit
b9475d6ebe
|
@ -2427,6 +2427,8 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
msg.timeout = 0;
|
msg.timeout = 0;
|
||||||
msg.device = SERIAL_CONTROL_DEV_SHELL;
|
msg.device = SERIAL_CONTROL_DEV_SHELL;
|
||||||
msg.count = _mavlink_shell->read(msg.data, sizeof(msg.data));
|
msg.count = _mavlink_shell->read(msg.data, sizeof(msg.data));
|
||||||
|
msg.target_system = _mavlink_shell->targetSysid();
|
||||||
|
msg.target_component = _mavlink_shell->targetCompid();
|
||||||
mavlink_msg_serial_control_send_struct(get_channel(), &msg);
|
mavlink_msg_serial_control_send_struct(get_channel(), &msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1778,6 +1778,7 @@ MavlinkReceiver::handle_message_serial_control(mavlink_message_t *msg)
|
||||||
if (shell) {
|
if (shell) {
|
||||||
// we ignore the timeout, EXCLUSIVE & BLOCKING flags of the SERIAL_CONTROL message
|
// we ignore the timeout, EXCLUSIVE & BLOCKING flags of the SERIAL_CONTROL message
|
||||||
if (serial_control_mavlink.count > 0) {
|
if (serial_control_mavlink.count > 0) {
|
||||||
|
shell->setTargetID(msg->sysid, msg->compid);
|
||||||
shell->write(serial_control_mavlink.data, serial_control_mavlink.count);
|
shell->write(serial_control_mavlink.data, serial_control_mavlink.count);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -42,6 +42,7 @@
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <px4_platform_common/tasks.h>
|
#include <px4_platform_common/tasks.h>
|
||||||
|
#include <px4_platform_common/atomic.h>
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
@ -77,8 +78,15 @@ public:
|
||||||
*/
|
*/
|
||||||
size_t available();
|
size_t available();
|
||||||
|
|
||||||
|
void setTargetID(uint8_t sysid, uint8_t compid) { _target_sysid.store(sysid); _target_compid.store(compid); }
|
||||||
|
|
||||||
|
uint8_t targetSysid() const { return _target_sysid.load(); }
|
||||||
|
uint8_t targetCompid() const { return _target_compid.load(); }
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
px4::atomic<uint8_t> _target_sysid{};
|
||||||
|
px4::atomic<uint8_t> _target_compid{};
|
||||||
|
|
||||||
int _to_shell_fd = -1; /** fd to write to the shell */
|
int _to_shell_fd = -1; /** fd to write to the shell */
|
||||||
int _from_shell_fd = -1; /** fd to read from the shell */
|
int _from_shell_fd = -1; /** fd to read from the shell */
|
||||||
int _shell_fds[2] = { -1, -1}; /** stdin & out used by the shell */
|
int _shell_fds[2] = { -1, -1}; /** stdin & out used by the shell */
|
||||||
|
|
Loading…
Reference in New Issue