Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
5fcd18eb
Commit
5fcd18eb
authored
Aug 13, 2011
by
lm
Browse files
Ported a larger portion to MAVLink v1.0
parent
1f23f9cb
Changes
2
Hide whitespace changes
Inline
Side-by-side
src/uas/UAS.cc
View file @
5fcd18eb
...
@@ -1216,58 +1216,49 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
...
@@ -1216,58 +1216,49 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
}
}
void
UAS
::
startRadioControlCalibration
()
void
UAS
::
startRadioControlCalibration
()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_DO_RC_CALIB;
// sendMessage(msg);
}
void
UAS
::
startDataRecording
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
//
mavlink_msg_
action
_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_
ACTION_REC_START
);
mavlink_msg_
command
_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_
CMD_PREFLIGHT_CALIBRATION
,
1
,
0
,
0
,
0
,
1
);
//
sendMessage(msg);
sendMessage
(
msg
);
}
}
void
UAS
::
pause
DataRecording
()
void
UAS
::
start
DataRecording
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
mavlink_msg_command_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
MAV_CMD_DO_CONTROL_VIDEO
,
1
,
-
1
,
-
1
,
-
1
,
2
);
// mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
sendMessage
(
msg
);
// sendMessage(msg);
}
}
void
UAS
::
stopDataRecording
()
void
UAS
::
stopDataRecording
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
mavlink_msg_command_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
MAV_CMD_DO_CONTROL_VIDEO
,
1
,
-
1
,
-
1
,
-
1
,
0
);
// mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
sendMessage
(
msg
);
// sendMessage(msg);
}
}
void
UAS
::
startMagnetometerCalibration
()
void
UAS
::
startMagnetometerCalibration
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
//
mavlink_msg_
action
_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_
ACTION_CALIBRATE_MAG
);
mavlink_msg_
command
_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_
CMD_PREFLIGHT_CALIBRATION
,
1
,
0
,
1
,
0
,
0
);
//
sendMessage(msg);
sendMessage
(
msg
);
}
}
void
UAS
::
startGyroscopeCalibration
()
void
UAS
::
startGyroscopeCalibration
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
//
mavlink_msg_
action
_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_
ACTION_CALIBRATE_GYRO
);
mavlink_msg_
command
_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_
CMD_PREFLIGHT_CALIBRATION
,
1
,
1
,
0
,
0
,
0
);
//
sendMessage(msg);
sendMessage
(
msg
);
}
}
void
UAS
::
startPressureCalibration
()
void
UAS
::
startPressureCalibration
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
//
mavlink_msg_
action
_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_
ACTION_CALIBRATE_PRESSURE
);
mavlink_msg_
command
_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_
CMD_PREFLIGHT_CALIBRATION
,
1
,
0
,
0
,
1
,
0
);
//
sendMessage(msg);
sendMessage
(
msg
);
}
}
quint64
UAS
::
getUnixReferenceTime
(
quint64
time
)
quint64
UAS
::
getUnixReferenceTime
(
quint64
time
)
...
@@ -1658,27 +1649,21 @@ void UAS::requestParameters()
...
@@ -1658,27 +1649,21 @@ void UAS::requestParameters()
{
{
mavlink_message_t
msg
;
mavlink_message_t
msg
;
mavlink_msg_param_request_list_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
this
->
getUASID
(),
25
);
mavlink_msg_param_request_list_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
this
->
getUASID
(),
25
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
}
}
void
UAS
::
writeParametersToStorage
()
void
UAS
::
writeParametersToStorage
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
mavlink_msg_command_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
MAV_CMD_PREFLIGHT_STORAGE
,
1
,
1
,
-
1
,
-
1
,
-
1
);
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
sendMessage
(
msg
);
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE);
// //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
// sendMessage(msg);
}
}
void
UAS
::
readParametersFromStorage
()
void
UAS
::
readParametersFromStorage
()
{
{
// FIXME MAVLINKV10PORTINGNEEDED
mavlink_message_t
msg
;
// mavlink_message_t msg;
mavlink_msg_command_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
MAV_CMD_PREFLIGHT_STORAGE
,
1
,
0
,
-
1
,
-
1
,
-
1
);
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
sendMessage
(
msg
);
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(uint8_t)MAV_ACTION_STORAGE_READ);
// sendMessage(msg);
}
}
void
UAS
::
enableAllDataTransmission
(
int
rate
)
void
UAS
::
enableAllDataTransmission
(
int
rate
)
...
...
src/uas/UAS.h
View file @
5fcd18eb
...
@@ -380,7 +380,6 @@ public slots:
...
@@ -380,7 +380,6 @@ public slots:
void
startPressureCalibration
();
void
startPressureCalibration
();
void
startDataRecording
();
void
startDataRecording
();
void
pauseDataRecording
();
void
stopDataRecording
();
void
stopDataRecording
();
signals:
signals:
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment