Browse Source

Merged master

sbg
Lorenz Meier 10 years ago
parent
commit
085a69383a
  1. 7
      ROMFS/px4fmu_common/init.d/rcS
  2. 7
      src/drivers/hil/hil.cpp
  3. 50
      src/modules/mavlink/mavlink_main.cpp

7
ROMFS/px4fmu_common/init.d/rcS

@ -101,9 +101,10 @@ then
fi fi
fi fi
if pca8574 start # Currently unused, but might be useful down the road
then #if pca8574 start
fi #then
#fi
# #
# Set default values # Set default values

7
src/drivers/hil/hil.cpp

@ -347,10 +347,9 @@ HIL::task_main()
/* advertise the mixed control outputs */ /* advertise the mixed control outputs */
actuator_outputs_s outputs; actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs)); memset(&outputs, 0, sizeof(outputs));
/* advertise the mixed control outputs */
int dummy; /* advertise the mixed control outputs, insist on the first group output */
_t_outputs = orb_advertise_multi(ORB_ID(actuator_outputs), _t_outputs = orb_advertise(ORB_ID(actuator_outputs), &outputs);
&outputs, &dummy, ORB_PRIO_LOW);
px4_pollfd_struct_t fds[2]; px4_pollfd_struct_t fds[2];
fds[0].fd = _t_actuators; fds[0].fd = _t_actuators;

50
src/modules/mavlink/mavlink_main.cpp

@ -807,6 +807,7 @@ Mavlink::get_free_tx_buf()
enable_flow_control(false); enable_flow_control(false);
} }
} }
#endif #endif
return buf_free; return buf_free;
@ -936,6 +937,7 @@ Mavlink::resend_message(mavlink_message_t *msg)
_last_write_success_time = _last_write_try_time; _last_write_success_time = _last_write_try_time;
count_txbytes(packet_len); count_txbytes(packet_len);
} }
#endif #endif
pthread_mutex_unlock(&_send_mutex); pthread_mutex_unlock(&_send_mutex);
@ -1016,7 +1018,8 @@ Mavlink::send_statustext(unsigned char severity, const char *string)
mavlink_logbuffer_write(&_logbuffer, &logmsg); mavlink_logbuffer_write(&_logbuffer, &logmsg);
} }
void Mavlink::send_autopilot_capabilites() { void Mavlink::send_autopilot_capabilites()
{
struct vehicle_status_s status; struct vehicle_status_s status;
MavlinkOrbSubscription *status_sub = this->add_orb_subscription(ORB_ID(vehicle_status)); MavlinkOrbSubscription *status_sub = this->add_orb_subscription(ORB_ID(vehicle_status));
@ -1039,16 +1042,16 @@ void Mavlink::send_autopilot_capabilites() {
memcpy(&msg.flight_custom_version, &px4_git_version_binary, sizeof(msg.flight_custom_version)); memcpy(&msg.flight_custom_version, &px4_git_version_binary, sizeof(msg.flight_custom_version));
memcpy(&msg.middleware_custom_version, &px4_git_version_binary, sizeof(msg.middleware_custom_version)); memcpy(&msg.middleware_custom_version, &px4_git_version_binary, sizeof(msg.middleware_custom_version));
memset(&msg.os_custom_version, 0, sizeof(msg.os_custom_version)); memset(&msg.os_custom_version, 0, sizeof(msg.os_custom_version));
#ifdef CONFIG_CDCACM_VENDORID #ifdef CONFIG_CDCACM_VENDORID
msg.vendor_id = CONFIG_CDCACM_VENDORID; msg.vendor_id = CONFIG_CDCACM_VENDORID;
#else #else
msg.vendor_id = 0; msg.vendor_id = 0;
#endif #endif
#ifdef CONFIG_CDCACM_PRODUCTID #ifdef CONFIG_CDCACM_PRODUCTID
msg.product_id = CONFIG_CDCACM_PRODUCTID; msg.product_id = CONFIG_CDCACM_PRODUCTID;
#else #else
msg.product_id = 0; msg.product_id = 0;
#endif #endif
uint32_t uid[3]; uint32_t uid[3];
mcu_unique_id(uid); mcu_unique_id(uid);
msg.uid = (((uint64_t)uid[1]) << 32) | uid[2]; msg.uid = (((uint64_t)uid[1]) << 32) | uid[2];
@ -1349,16 +1352,19 @@ Mavlink::task_main(int argc, char *argv[])
_datarate = 0; _datarate = 0;
_mode = MAVLINK_MODE_NORMAL; _mode = MAVLINK_MODE_NORMAL;
#ifdef __PX4_NUTTX /*
/* work around some stupidity in task_create's argv handling */ * Called via create_task with taskname followed by original argv
argc -= 2; * <name> mavlink start
argv += 2; *
#endif * Remove all 3
*/
argc -= 3;
argv += 3;
/* don't exit from getopt loop to leave getopt global variables in consistent state, /* don't exit from getopt loop to leave getopt global variables in consistent state,
* set error flag instead */ * set error flag instead */
bool err_flag = false; bool err_flag = false;
int myoptind=1; int myoptind = 1;
const char *myoptarg = NULL; const char *myoptarg = NULL;
char* eptr; char* eptr;
int temp_int_arg; int temp_int_arg;
@ -1412,6 +1418,7 @@ Mavlink::task_main(int argc, char *argv[])
} else if (strcmp(myoptarg, "camera") == 0) { } else if (strcmp(myoptarg, "camera") == 0) {
// left in here for compatibility // left in here for compatibility
_mode = MAVLINK_MODE_ONBOARD; _mode = MAVLINK_MODE_ONBOARD;
} else if (strcmp(myoptarg, "onboard") == 0) { } else if (strcmp(myoptarg, "onboard") == 0) {
_mode = MAVLINK_MODE_ONBOARD; _mode = MAVLINK_MODE_ONBOARD;
} }
@ -1486,6 +1493,7 @@ Mavlink::task_main(int argc, char *argv[])
warn("could not open %s", _device_name); warn("could not open %s", _device_name);
return ERROR; return ERROR;
} }
#endif #endif
/* initialize send mutex */ /* initialize send mutex */
@ -1821,11 +1829,11 @@ Mavlink::start(int argc, char *argv[])
// task - start_helper() only returns // task - start_helper() only returns
// when the started task exits. // when the started task exits.
px4_task_spawn_cmd(buf, px4_task_spawn_cmd(buf,
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT, SCHED_PRIORITY_DEFAULT,
2400, 2400,
(px4_main_t)&Mavlink::start_helper, (px4_main_t)&Mavlink::start_helper,
(char * const *)argv); (char *const *)argv);
// Ensure that this shell command // Ensure that this shell command
// does not return before the instance // does not return before the instance
@ -1905,6 +1913,12 @@ Mavlink::stream_command(int argc, char *argv[])
bool provided_device = false; bool provided_device = false;
bool provided_network_port = false; bool provided_network_port = false;
/*
* Called via main with original argv
* mavlink start
*
* Remove 2
*/
argc -= 2; argc -= 2;
argv += 2; argv += 2;

Loading…
Cancel
Save