Updated documentation, re-introduced quad messages

This commit is contained in:
LM
2012-03-19 13:19:00 +01:00
parent b4d57db96b
commit d5457c9505
3 changed files with 74 additions and 16 deletions
+29 -3
View File
@@ -1,5 +1,31 @@
body {
font-family:'Helvetica',Arial;
font-size:90%;
margin: 80px;
}
h1 {
margin-top: 2em;
}
h2 {
margin-top: 1em;
}
h3 {
margin-top: 0.8em;
font-size:150%;
}
p.description {
font-style:italic;
}
table {
margin-bottom: 5em;
}
table.sortable {
spacing: 5px;
border: 1px solid #656575;
width: 100%;
}
@@ -8,8 +34,8 @@ table.sortable th {
margin: 5px;
}
tr:nth-child(odd) { background-color:#eee; }
tr:nth-child(even) { background-color:#fff; }
#tr:nth-child(odd) { background-color:#eee; }
#tr:nth-child(even) { background-color:#fff; }
table.sortable thead {
background-color:#eee;
+29 -13
View File
@@ -1,4 +1,4 @@
<?php>
<?php
// Requires the installation of php5-xsl
// e.g. on Debian/Ubuntu: sudo apt-get install php5-xsl
@@ -6,14 +6,12 @@
// Load the file from the repository / server.
// Update this URL if the file location changes
$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml";
$xml_file_name = "https://raw.github.com/mavlink/mavlink/master/message_definitions/v1.0/common.xml";
// Load the XSL transformation file from the repository / server.
// This file can be updated by any client to adjust the table
$xsl_file_name= "http://github.com/pixhawk/mavlink/raw/master/doc/mavlink_to_html_table.xsl";
$xsl_file_name= "https://raw.github.com/mavlink/mavlink/master/doc/mavlink_to_html_table.xsl";
// Load data XML file
$xml = file_get_contents($xml_file_name);
@@ -27,7 +25,22 @@ $xsl_doc->loadXML($xsl);
$xsltproc = new XsltProcessor();
$xsltproc->importStylesheet($xsl_doc);
?>
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01//EN">
<html>
<head>
<title>MAVLINK Common Message set specifications</title>
<link rel="stylesheet" type="text/css" href="mavlink.css">
</head>
<body>
<h1>MAVLINK Common Message Set</h1>
<p>
These messages define the common message set, which is the reference message set implemented by most ground control stations and autopilots.
</p>
<?php
// process the files and write the output to $out_file
if ($html = $xsltproc->transformToXML($xml_doc))
{
@@ -35,19 +48,22 @@ if ($html = $xsltproc->transformToXML($xml_doc))
}
else
{
trigger_error('XSL transformation failed.',E_USER_ERROR);
trigger_error("XSL transformation failed",E_USER_ERROR);
}
</php>
?>
<br />
<br />
<h2> Messages XML Definition </h2>
Messages are defined by the <a href="http://github.com/pixhawk/mavlink/blob/master/mavlink_standard_message.xml">mavlink_standard_message.xml</a> file. The C packing/unpacking code is generated from this specification, as well as the HTML documentaiton in the section above.<br />
<p>
Messages are defined by the <a href="https://raw.github.com/mavlink/mavlink/master/message_definitions/v1.0/common.xml">common.xml</a> file. The C packing/unpacking code is generated from this specification, as well as the HTML documentaiton in the section above.<br />
<br />
<i>The XML displayed here is updated on every commit and therefore up-to-date.</i>
<?php>
</p>
</body>
</html>
<?php
//require_once("inc/geshi.php");
//$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml";
//
@@ -60,4 +76,4 @@ Messages are defined by the <a href="http://github.com/pixhawk/mavlink/blob/mast
//
//echo $display_xml;
</php>
?>
+16
View File
@@ -1199,6 +1199,22 @@
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="60" name="SET_QUAD_MOTORS_SETPOINT">
<description>Setpoint in the four motor speeds</description>
<field type="uint8_t" name="target_system">System ID of the system that should set these motor commands</field>
<field type="uint16_t" name="motor_front_nw">Front motor in + configuration, front left motor in x configuration</field>
<field type="uint16_t" name="motor_right_ne">Right motor in + configuration, front right motor in x configuration</field>
<field type="uint16_t" name="motor_back_se">Back motor in + configuration, back right motor in x configuration</field>
<field type="uint16_t" name="motor_left_sw">Left motor in + configuration, back left motor in x configuration</field>
</message>
<message id="61" name="SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST">
<description></description>
<field type="uint8_t[6]" name="target_systems">System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs</field>
<field type="int16_t[6]" name="roll">Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="pitch">Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="yaw">Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="uint16_t[6]" name="thrust">Collective thrust, scaled to uint16 for 6 quadrotors: 0..5</field>
</message>
<message id="62" name="NAV_CONTROLLER_OUTPUT">
<description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs
of the controller before actual flight and to assist with tuning controller parameters.</description>