aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-10 12:13:40 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-10 12:13:40 +0100
commit90466afe05359cd5fc1d5b44b13d73912fb6571b (patch)
tree3c1bf907ba51433533867d05b73ec4c9292fd067
parent15f43b1acc456ae47bac0575e785ed87d95db93c (diff)
downloadpx4-firmware-90466afe05359cd5fc1d5b44b13d73912fb6571b.tar.gz
px4-firmware-90466afe05359cd5fc1d5b44b13d73912fb6571b.tar.bz2
px4-firmware-90466afe05359cd5fc1d5b44b13d73912fb6571b.zip
Comments cleanup / polishing
-rw-r--r--apps/mavlink/mavlink_receiver.c4
-rw-r--r--apps/mavlink/orb_listener.c4
-rw-r--r--apps/multirotor_pos_control/multirotor_pos_control.c6
-rw-r--r--apps/sensors/sensors.cpp4
-rw-r--r--apps/uORB/topics/subsystem_info.h12
5 files changed, 20 insertions, 10 deletions
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 39e574c04..e1a4e8e8a 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +35,8 @@
/**
* @file mavlink_receiver.c
* MAVLink protocol message receive and dispatch
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
/* XXX trim includes */
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 683964a0d..fafc8f79c 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +35,8 @@
/**
* @file orb_listener.c
* Monitors ORB topics and sends update messages as appropriate.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
// XXX trim includes
diff --git a/apps/multirotor_pos_control/multirotor_pos_control.c b/apps/multirotor_pos_control/multirotor_pos_control.c
index 9821fc7e5..7b8d83aa8 100644
--- a/apps/multirotor_pos_control/multirotor_pos_control.c
+++ b/apps/multirotor_pos_control/multirotor_pos_control.c
@@ -32,8 +32,10 @@
*
****************************************************************************/
-/*
- * @file Implementation of AR.Drone 1.0 / 2.0 control interface
+/**
+ * @file multirotor_pos_control.c
+ *
+ * Skeleton for multirotor position controller
*/
#include <nuttx/config.h>
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index 3e9f35eaf..675a8602a 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -34,9 +34,9 @@
/**
* @file sensors.cpp
- * @author Lorenz Meier <lm@inf.ethz.ch>
- *
* Sensor readout process.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
diff --git a/apps/uORB/topics/subsystem_info.h b/apps/uORB/topics/subsystem_info.h
index 89b397478..c3e039d66 100644
--- a/apps/uORB/topics/subsystem_info.h
+++ b/apps/uORB/topics/subsystem_info.h
@@ -1,9 +1,9 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +37,10 @@
/**
* @file subsystem_info.h
* Definition of the subsystem info topic.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef TOPIC_SUBSYSTEM_INFO_H_