Plane: fixed MAVLink target IDs in fence point message
thanks to Kevin Hester for finding this
This commit is contained in:
parent
8b87d3643b
commit
36ff950b12
@ -1687,7 +1687,7 @@ mission_failed:
|
|||||||
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
|
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
|
||||||
} else {
|
} else {
|
||||||
Vector2l point = get_fence_point_with_index(packet.idx);
|
Vector2l point = get_fence_point_with_index(packet.idx);
|
||||||
mavlink_msg_fence_point_send(chan, 0, 0, packet.idx, g.fence_total,
|
mavlink_msg_fence_point_send(chan, msg->sysid, msg->compid, packet.idx, g.fence_total,
|
||||||
point.x*1.0e-7, point.y*1.0e-7);
|
point.x*1.0e-7, point.y*1.0e-7);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user