Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE PM_ELEC PACKING
2
 
3
#define MAVLINK_MSG_ID_PM_ELEC 188
4
 
5
typedef struct __mavlink_pm_elec_t
6
{
7
 float PwCons; ///< current power consumption
8
 float BatStat; ///< battery status
9
 float PwGen[3]; ///< Power generation from each module
10
} mavlink_pm_elec_t;
11
 
12
#define MAVLINK_MSG_ID_PM_ELEC_LEN 20
13
#define MAVLINK_MSG_ID_188_LEN 20
14
 
15
#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3
16
 
17
#define MAVLINK_MESSAGE_INFO_PM_ELEC { \
18
        "PM_ELEC", \
19
        3, \
20
        {  { "PwCons", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pm_elec_t, PwCons) }, \
21
         { "BatStat", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pm_elec_t, BatStat) }, \
22
         { "PwGen", NULL, MAVLINK_TYPE_FLOAT, 3, 8, offsetof(mavlink_pm_elec_t, PwGen) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a pm_elec message
29
 * @param system_id ID of this system
30
 * @param component_id ID of this component (e.g. 200 for IMU)
31
 * @param msg The MAVLink message to compress the data into
32
 *
33
 * @param PwCons current power consumption
34
 * @param BatStat battery status
35
 * @param PwGen Power generation from each module
36
 * @return length of the message in bytes (excluding serial stream start sign)
37
 */
38
static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39
                                                       float PwCons, float BatStat, const float *PwGen)
40
{
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42
        char buf[20];
43
        _mav_put_float(buf, 0, PwCons);
44
        _mav_put_float(buf, 4, BatStat);
45
        _mav_put_float_array(buf, 8, PwGen, 3);
46
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
47
#else
48
        mavlink_pm_elec_t packet;
49
        packet.PwCons = PwCons;
50
        packet.BatStat = BatStat;
51
        mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
52
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
53
#endif
54
 
55
        msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
56
        return mavlink_finalize_message(msg, system_id, component_id, 20, 170);
57
}
58
 
59
/**
60
 * @brief Pack a pm_elec message on a channel
61
 * @param system_id ID of this system
62
 * @param component_id ID of this component (e.g. 200 for IMU)
63
 * @param chan The MAVLink channel this message was sent over
64
 * @param msg The MAVLink message to compress the data into
65
 * @param PwCons current power consumption
66
 * @param BatStat battery status
67
 * @param PwGen Power generation from each module
68
 * @return length of the message in bytes (excluding serial stream start sign)
69
 */
70
static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
71
                                                           mavlink_message_t* msg,
72
                                                           float PwCons,float BatStat,const float *PwGen)
73
{
74
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75
        char buf[20];
76
        _mav_put_float(buf, 0, PwCons);
77
        _mav_put_float(buf, 4, BatStat);
78
        _mav_put_float_array(buf, 8, PwGen, 3);
79
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
80
#else
81
        mavlink_pm_elec_t packet;
82
        packet.PwCons = PwCons;
83
        packet.BatStat = BatStat;
84
        mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
85
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
86
#endif
87
 
88
        msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
89
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 170);
90
}
91
 
92
/**
93
 * @brief Encode a pm_elec struct into a message
94
 *
95
 * @param system_id ID of this system
96
 * @param component_id ID of this component (e.g. 200 for IMU)
97
 * @param msg The MAVLink message to compress the data into
98
 * @param pm_elec C-struct to read the message contents from
99
 */
100
static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec)
101
{
102
        return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
103
}
104
 
105
/**
106
 * @brief Send a pm_elec message
107
 * @param chan MAVLink channel to send the message
108
 *
109
 * @param PwCons current power consumption
110
 * @param BatStat battery status
111
 * @param PwGen Power generation from each module
112
 */
113
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
114
 
115
static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen)
116
{
117
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
118
        char buf[20];
119
        _mav_put_float(buf, 0, PwCons);
120
        _mav_put_float(buf, 4, BatStat);
121
        _mav_put_float_array(buf, 8, PwGen, 3);
122
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, 20, 170);
123
#else
124
        mavlink_pm_elec_t packet;
125
        packet.PwCons = PwCons;
126
        packet.BatStat = BatStat;
127
        mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
128
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, 20, 170);
129
#endif
130
}
131
 
132
#endif
133
 
134
// MESSAGE PM_ELEC UNPACKING
135
 
136
 
137
/**
138
 * @brief Get field PwCons from pm_elec message
139
 *
140
 * @return current power consumption
141
 */
142
static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg)
143
{
144
        return _MAV_RETURN_float(msg,  0);
145
}
146
 
147
/**
148
 * @brief Get field BatStat from pm_elec message
149
 *
150
 * @return battery status
151
 */
152
static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg)
153
{
154
        return _MAV_RETURN_float(msg,  4);
155
}
156
 
157
/**
158
 * @brief Get field PwGen from pm_elec message
159
 *
160
 * @return Power generation from each module
161
 */
162
static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float *PwGen)
163
{
164
        return _MAV_RETURN_float_array(msg, PwGen, 3,  8);
165
}
166
 
167
/**
168
 * @brief Decode a pm_elec message into a struct
169
 *
170
 * @param msg The message to decode
171
 * @param pm_elec C-struct to decode the message contents into
172
 */
173
static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec)
174
{
175
#if MAVLINK_NEED_BYTE_SWAP
176
        pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg);
177
        pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg);
178
        mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen);
179
#else
180
        memcpy(pm_elec, _MAV_PAYLOAD(msg), 20);
181
#endif
182
}