aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-07-10 14:11:25 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-07-10 14:11:25 +0200
commitfc1669b0969890456f9151dd9719af87df62e69c (patch)
treeceee6fa9a7642b4ef2b63921299c006987add5a8 /src/modules/mavlink
parent9b2d444cc56eaaedcf271f200b93dcca94623209 (diff)
parent58cae259e40a3dcab132f42348d57767fca600a1 (diff)
downloadpx4-firmware-fc1669b0969890456f9151dd9719af87df62e69c.tar.gz
px4-firmware-fc1669b0969890456f9151dd9719af87df62e69c.tar.bz2
px4-firmware-fc1669b0969890456f9151dd9719af87df62e69c.zip
Merge branch master into dataman_state_nav_rewrite
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp26
-rw-r--r--src/modules/mavlink/mavlink_ftp.h27
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp61
-rw-r--r--src/modules/mavlink/mavlink_receiver.h9
4 files changed, 59 insertions, 64 deletions
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 55a472bf6..675a6870e 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -117,10 +117,10 @@ MavlinkFTP::_worker(Request *req)
if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
errorCode = kErrNoRequest;
goto out;
- printf("ftp: bad crc\n");
+ warnx("ftp: bad crc");
}
- printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+ //printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
switch (hdr->opcode) {
case kCmdNone:
@@ -167,9 +167,9 @@ out:
// handle success vs. error
if (errorCode == kErrNone) {
hdr->opcode = kRspAck;
- printf("FTP: ack\n");
+ //warnx("FTP: ack\n");
} else {
- printf("FTP: nak %u\n", errorCode);
+ warnx("FTP: nak %u", errorCode);
hdr->opcode = kRspNak;
hdr->size = 1;
hdr->data[0] = errorCode;
@@ -199,12 +199,18 @@ MavlinkFTP::ErrorCode
MavlinkFTP::_workList(Request *req)
{
auto hdr = req->header();
- DIR *dp = opendir(req->dataAsCString());
+
+ char dirPath[kMaxDataLength];
+ strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+
+ DIR *dp = opendir(dirPath);
if (dp == nullptr) {
- printf("FTP: can't open path '%s'\n", req->dataAsCString());
+ warnx("FTP: can't open path '%s'", dirPath);
return kErrNotDir;
}
+
+ //warnx("FTP: list %s offset %d", dirPath, hdr->offset);
ErrorCode errorCode = kErrNone;
struct dirent entry, *result = nullptr;
@@ -216,6 +222,7 @@ MavlinkFTP::_workList(Request *req)
for (;;) {
// read the directory entry
if (readdir_r(dp, &entry, &result)) {
+ warnx("FTP: list %s readdir_r failure\n", dirPath);
errorCode = kErrIO;
break;
}
@@ -251,8 +258,8 @@ MavlinkFTP::_workList(Request *req)
// copy the name, which we know will fit
strcpy((char *)&hdr->data[offset], entry.d_name);
+ //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
offset += strlen(entry.d_name) + 1;
- printf("FTP: list %s\n", entry.d_name);
}
closedir(dp);
@@ -297,19 +304,20 @@ MavlinkFTP::_workRead(Request *req)
}
// Seek to the specified position
- printf("Seek %d\n", hdr->offset);
+ //warnx("seek %d", hdr->offset);
if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
// Unable to see to the specified location
+ warnx("seek fail");
return kErrEOF;
}
int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
if (bytes_read < 0) {
// Negative return indicates error other than eof
+ warnx("read fail %d", bytes_read);
return kErrIO;
}
- printf("Read success %d\n", bytes_read);
hdr->size = bytes_read;
return kErrNone;
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index e22e61553..59237a4c4 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -147,20 +147,21 @@ private:
unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
_mavlink->get_channel(), &msg, sequence(), rawData());
- _mavlink->lockMessageBufferMutex();
- bool fError = _mavlink->message_buffer_write(&msg, len);
- _mavlink->unlockMessageBufferMutex();
-
- if (!fError) {
+ _mavlink->lockMessageBufferMutex();
+ bool success = _mavlink->message_buffer_write(&msg, len);
+ _mavlink->unlockMessageBufferMutex();
+
+ if (!success) {
warnx("FTP TX ERR");
- } else {
- warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
- _mavlink->get_system_id(),
- _mavlink->get_component_id(),
- _mavlink->get_channel(),
- len,
- msg.checksum);
- }
+ }
+ // else {
+ // warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
+ // _mavlink->get_system_id(),
+ // _mavlink->get_component_id(),
+ // _mavlink->get_channel(),
+ // len,
+ // msg.checksum);
+ // }
}
uint8_t *rawData() { return &_message.data[0]; }
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index f3fb34bba..99ec98ee9 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -101,18 +101,25 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_cmd_pub(-1),
_flow_pub(-1),
_offboard_control_sp_pub(-1),
+ _local_pos_sp_pub(-1),
+ _global_vel_sp_pub(-1),
+ _att_sp_pub(-1),
+ _rates_sp_pub(-1),
_vicon_position_pub(-1),
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
_telemetry_heartbeat_time(0),
_radio_status_available(false),
+ _control_mode_sub(-1),
_hil_frames(0),
_old_timestamp(0),
_hil_local_proj_inited(0),
_hil_local_alt0(0.0)
{
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
memset(&hil_local_pos, 0, sizeof(hil_local_pos));
+ memset(&_control_mode, 0, sizeof(_control_mode));
// make sure the FTP server is started
(void)MavlinkFTP::getServer();
@@ -358,53 +365,21 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
void
MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
{
- mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
- mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
+ mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
+ mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control);
- if (mavlink_system.sysid < 4) {
+ /* Only accept system IDs from 1 to 4 */
+ if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) {
struct offboard_control_setpoint_s offboard_control_sp;
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));
- uint8_t ml_mode = 0;
- bool ml_armed = false;
+ /* Convert values * 1000 back */
+ offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
- switch (quad_motors_setpoint.mode) {
- case 0:
- ml_armed = false;
- break;
-
- case 1:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
- ml_armed = true;
-
- break;
-
- case 2:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
- ml_armed = true;
-
- break;
-
- case 3:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
- break;
-
- case 4:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
- break;
- }
-
- offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
-
- if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
- ml_armed = false;
- }
-
- offboard_control_sp.armed = ml_armed;
- offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);
+ offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
offboard_control_sp.timestamp = hrt_absolute_time();
@@ -466,6 +441,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
manual.r = man.r / 1000.0f;
manual.z = man.z / 1000.0f;
+ warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z);
+
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 80e0ea813..8d38b9973 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -36,6 +36,7 @@
* MAVLink 1.0 uORB listener definition
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#pragma once
@@ -44,6 +45,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -53,6 +55,7 @@
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
@@ -122,6 +125,7 @@ private:
mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos;
+ struct vehicle_control_mode_s _control_mode;
orb_advert_t _global_pos_pub;
orb_advert_t _local_pos_pub;
orb_advert_t _attitude_pub;
@@ -136,12 +140,17 @@ private:
orb_advert_t _cmd_pub;
orb_advert_t _flow_pub;
orb_advert_t _offboard_control_sp_pub;
+ orb_advert_t _local_pos_sp_pub;
+ orb_advert_t _global_vel_sp_pub;
+ orb_advert_t _att_sp_pub;
+ orb_advert_t _rates_sp_pub;
orb_advert_t _vicon_position_pub;
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
hrt_abstime _telemetry_heartbeat_time;
bool _radio_status_available;
+ int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;
bool _hil_local_proj_inited;