distance_sensor: added msg definition to 'msg' folder

This commit is contained in:
TSC21 2015-05-20 12:40:15 +01:00
parent 796b105382
commit c180b5d825
3 changed files with 50 additions and 26 deletions

View File

@ -80,6 +80,7 @@ add_message_files(
vehicle_global_velocity_setpoint.msg vehicle_global_velocity_setpoint.msg
offboard_control_mode.msg offboard_control_mode.msg
vehicle_force_setpoint.msg vehicle_force_setpoint.msg
distance_sensor.msg
) )
## Generate services in the 'srv' folder ## Generate services in the 'srv' folder

17
msg/distance_sensor.msg Normal file
View File

@ -0,0 +1,17 @@
# DISTANCE_SENSOR message data
uint32 time_boot_ms
uint16 min_distance
uint16 max_distance
uint16 current_distance
uint8 type
uint8 MAV_DISTANCE_SENSOR_LASER = 0
uint8 MAV_DISTANCE_SENSOR_ULTRASOUND = 1
uint8 MAV_DISTANCE_SENSOR_INFRARED = 2
uint8 id
uint8 orientation
uint8 covariance

View File

@ -1,7 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2015 PX4 Development Team. All rights reserved. * Copyright (C) 2013-2015 PX4 Development Team. All rights reserved.
* Author: @author Nuno Marques <n.marques21@hotmail.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -32,38 +31,47 @@
* *
****************************************************************************/ ****************************************************************************/
/** /* Auto-generated by genmsg_cpp from file /home/nuno/px4/Firmware/msg/distance_sensor.msg */
* @file distance_sensor.h
* Definition of the distance sensor uORB topic.
*/
#ifndef TOPIC_DISTANCE_SENSOR_H_
#define TOPIC_DISTANCE_SENSOR_H_ #pragma once
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <uORB/uORB.h>
#include "../uORB.h"
#ifndef __cplusplus
#define MAV_DISTANCE_SENSOR_LASER 0
#define MAV_DISTANCE_SENSOR_ULTRASOUND 1
#define MAV_DISTANCE_SENSOR_INFRARED 2
#endif
/** /**
* @addtogroup topics * @addtogroup topics
* @{
*/ */
/**
* Distance sensor data, with range in centimeters (not in SI). #ifdef __cplusplus
* struct __EXPORT distance_sensor_s {
* @see http://en.wikipedia.org/wiki/International_System_of_Units #else
*/
struct distance_sensor_s { struct distance_sensor_s {
#endif
uint32_t time_boot_ms;
uint16_t min_distance;
uint16_t max_distance;
uint16_t current_distance;
uint8_t type;
uint8_t id;
uint8_t orientation;
uint8_t covariance;
#ifdef __cplusplus
static const uint8_t MAV_DISTANCE_SENSOR_LASER = 0;
static const uint8_t MAV_DISTANCE_SENSOR_ULTRASOUND = 1;
static const uint8_t MAV_DISTANCE_SENSOR_INFRARED = 2;
uint32_t time_boot_ms; /**< Time since system boot */ #endif
uint16_t min_distance; /**< Minimum distance the sensor can measure in centimeters */
uint16_t max_distance; /**< Maximum distance the sensor can measure in centimeters */
uint16_t current_distance; /**< Current distance reading */
uint8_t type; /**< Type from MAV_DISTANCE_SENSOR enum */
uint8_t id; /**< Onboard ID of the sensor */
uint8_t orientation; /**< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum */
uint8_t covariance; /**< Measurement covariance in centimeters, 0 for unknown / invalid readings */
}; };
/** /**
@ -72,5 +80,3 @@ struct distance_sensor_s {
/* register this as object request broker structure */ /* register this as object request broker structure */
ORB_DECLARE(distance_sensor); ORB_DECLARE(distance_sensor);
#endif