Browse Source

Merge branch 'master' of github.com:mavlink/qgroundcontrol into v10release

QGC4.4
hengli 13 years ago
parent
commit
6107c88979
  1. 30
      files/pixhawk/hexarotor/widgets/mavconn.qgw
  2. 1
      src/comm/MAVLinkProtocol.cc
  3. 5
      src/uas/UAS.cc
  4. 5
      src/uas/UASWaypointManager.cc
  5. 1
      src/uas/UASWaypointManager.h
  6. 5
      src/ui/WaypointList.cc

30
files/pixhawk/hexrotor/widgets/mavconn.qgw → files/pixhawk/hexarotor/widgets/mavconn.qgw

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
[MAVCONN%20Control]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=START Recording
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=DO: Control Video
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=CAPTURE
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=200
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
@ -12,7 +12,7 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 @@ -12,7 +12,7 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=STOP Recording
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=DO: Control Video
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=STOP
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=200
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
@ -35,4 +35,28 @@ QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 @@ -35,4 +35,28 @@ QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\size=3
QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Setpoint ON<->OFF
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=1
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=0
QGC_TOOL_WIDGET_ITEMS\5\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DESCRIPTION=Glob. Loc ON<->OFF
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_PARAMID=
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_COMPONENTID=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MIN=1
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MAX=0
QGC_TOOL_WIDGET_ITEMS\6\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DESCRIPTION=GPS ENU HL<->ASL
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_PARAMID=
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_COMPONENTID=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\7\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DESCRIPTION=Yaw PX<->ASL
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_PARAMID=
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_COMPONENTID=0
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\size=7

1
src/comm/MAVLinkProtocol.cc

@ -202,6 +202,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -202,6 +202,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// }
//#endif
#ifdef QGC_PROTOBUF_ENABLED
if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
{
mavlink_extended_message_t extended_message;

5
src/uas/UAS.cc

@ -987,7 +987,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -987,7 +987,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
#ifdef QGC_PROTOBUF_ENABLED
void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
{
if (!link) return;
if (!link)
{
return;
}
if (!links->contains(link))
{
addLink(link);

5
src/uas/UASWaypointManager.cc

@ -61,6 +61,11 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) @@ -61,6 +61,11 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
}
}
UASWaypointManager::~UASWaypointManager()
{
}
void UASWaypointManager::timeout()
{
if (current_retries > 0) {

1
src/uas/UASWaypointManager.h

@ -65,6 +65,7 @@ private: @@ -65,6 +65,7 @@ private:
public:
UASWaypointManager(UAS* uas=NULL); ///< Standard constructor
~UASWaypointManager();
/** @name Received message handlers */
/*@{*/

5
src/ui/WaypointList.cc

@ -155,7 +155,10 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, @@ -155,7 +155,10 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch,
void WaypointList::setUAS(UASInterface* uas)
{
//if (this->uas == NULL && uas != NULL)
if (this->uas == NULL && uas != NULL)
{
WPM = uas->getWaypointManager();
}
if (this->uas == NULL)
{
this->uas = uas;

Loading…
Cancel
Save