Com_SerialReadingThread.cpp 12 KB
Newer Older
1
2
3
4
5
6
7
/**
 *  @author Sylvain Colomer
 *  @date 18/04/19.
 *  trash-put /dev/shm/file
 */

#include "../include/Com_SerialReadingThread.h"
8
#include "../include/global_variables.h"
9
10
11
12

//#define DISPLAY


13
Serial_Port_ReadingThread::Serial_Port_ReadingThread(int task_period, int task_deadline):
14
15
16
    Abstract_ThreadClass(task_period, task_deadline)
{
    //Init object
17
   // Serial_Port_ReadingThread::drone1 = drone1;
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43

    //Init dictionnary
    //mavlink_dic
    //ifstream file1("test.txt", ios::in); 
    //std::string buffer1;
    /*if(file1)
    {
        
        while(getline(file1, buffer1))
        {
            std::cout << line << std::endl;
        }
    }
    else{
        std::cout<< "Error : unable to open file" << std::endl;
        exit(1);
    }
    */

    //Creation of blc channels
    //Example: blc_heartbeat = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.heartbeat", BLC_CHANNEL_WRITE, 'IN16', 'NDEF', 1, 6));

    //blc_local_position_ned = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.local_position_ned", BLC_CHANNEL_WRITE, 'IN16', 'NDEF', 1, 6));
    //blc_global_position_int = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.global_position_int", BLC_CHANNEL_WRITE, 'IN16', 'NDEF', 1, 6));
    // blc_position_target_local_ned = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.position_target_local_ned", BLC_CHANNEL_WRITE, 'IN16', 'NDEF', 1, 6));
    // blc_position_target_global_int = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.position_target_global_int", BLC_CHANNEL_WRITE, 'IN16', 'NDEF', 1, 6));
44
  //  blc_highres_imu = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.highres_imu", BLC_CHANNEL_WRITE, 'FL32', 'NDEF', 1, 9));
45
46
47
48
49
50
51
52
53
    // blc_attitude = std::shared_ptr<blc_channel>(new blc_channel("/pixhawk.sensors.attitude", BLC_CHANNEL_WRITE, 'FL32', 'NDEF', 1, 9));

}

Serial_Port_ReadingThread::~Serial_Port_ReadingThread()
{

}

54
55
void Serial_Port_ReadingThread::run()
{
56
57
58
59
60
61
62
63
    long long currentThreadDelay;
    bool success=false;

    gettimeofday(&begin, 0);
    gettimeofday(&front_checkpoint, 0);

    currentState = LifeCoreState::RUN;

64
65
    while(isRunFlag())
    {
66
67
68
69
70
        usleep(task_period);

        gettimeofday(&end_checkpoint, 0);
        currentThreadDelay=(end_checkpoint.tv_sec-front_checkpoint.tv_sec) * 1000000L + (end_checkpoint.tv_usec-front_checkpoint.tv_usec);

71
72
        if (currentThreadDelay > task_period )
        {
73
74
            gettimeofday(&front_checkpoint, 0);

75
76
            if (currentThreadDelay > task_period + task_deadline)
            {
77
78
                currentState = LifeCoreState::DEADLINE_EXCEEDED;
            }
79
80
            else 
            {
81
82
                currentState = LifeCoreState::RUN;
                mavlink_message_t message;
83
84
85
                success = drone1.read_message(message);
                if(success)
                {
86
87
88
89
90
91
92
                    read_messages(message);
                }
            }
        }
    }
}

93
94
void Serial_Port_ReadingThread::read_messages(mavlink_message_t message)
{
95
96
97
    std::string buffer1="";

    // Handle current timestamp
98
99
    drone1.timestamps = get_time_usec();
    buffer1 = "Time: "+std::to_string(drone1.timestamps);
100
101
102
103
104
105
106
107
108
    //Display_IHM::getInstanceOf().printData(buffer1, 7, 1);

    //Display_IHM::getInstanceOf().printLog(std::to_string(message.msgid));

    switch (message.msgid)
    {
        case MAVLINK_MSG_ID_HEARTBEAT:
        {
            //Display_IHM::getInstanceOf().printLog("heartbeat");
109
            mavlink_msg_heartbeat_decode(&message, &drone1.heartbeat);
110
            buffer1 = 
111
112
113
114
115
116
                "Hearthbeat:"+std::to_string(drone1.heartbeat.type)+
                " "+std::to_string(drone1.heartbeat.autopilot)+
                " "+std::to_string(drone1.heartbeat.base_mode)+
                " "+std::to_string(drone1.heartbeat.custom_mode)+
                " "+std::to_string(drone1.heartbeat.system_status)+
                " "+std::to_string(drone1.heartbeat.mavlink_version);
117
118
119
120
121
122
123
124
125

            //Display_IHM::getInstanceOf().printData(buffer1, 8, 1);

            break;
        }

        //ACK COMMAND
        case MAVLINK_MSG_ID_COMMAND_ACK:
        {
126
127
            mavlink_msg_command_ack_decode(&message, &drone1.ack);
            handle_command_ack(&drone1.ack);
128
129
130
131
132
133
            
            break;
        }

        case MAVLINK_MSG_ID_SYS_STATUS:
        {
134
135
            mavlink_msg_sys_status_decode(&message, &drone1.sys_status);
            buffer1 = "Error: "+std::to_string(drone1.sys_status.errors_count1)+" "+std::to_string(drone1.sys_status.errors_count2)+" "+std::to_string(drone1.sys_status.errors_count3)+" "+std::to_string(drone1.sys_status.errors_count4);
136
            //Display_IHM::getInstanceOf().printData(buffer1, 9, 1);
137
            buffer1 = "Voltage: "+std::to_string(drone1.sys_status.voltage_battery);
138
139
140
141
142
143
144
            //Display_IHM::getInstanceOf().printData(buffer1, 10, 1);
            
            break;
        }

        case MAVLINK_MSG_ID_BATTERY_STATUS:
        {
145
            mavlink_msg_battery_status_decode(&message, &drone1.battery_status);
146
147
148
149
150
            break;
        }

        case MAVLINK_MSG_ID_RADIO_STATUS:
        {
151
            mavlink_msg_radio_status_decode(&message, &drone1.radio_status);
152
153
154
155
156
157
            break;
        }

        //ACCELEROMETERS
        case MAVLINK_MSG_ID_HIGHRES_IMU:
        {
158
            mavlink_msg_highres_imu_decode(&message, &drone1.highres_imu);
159

160
            buffer1 = "Acc: "+std::to_string(drone1.highres_imu.xacc)+" "+std::to_string(drone1.highres_imu.yacc)+" "+std::to_string(drone1.highres_imu.zacc);
161
            //Display_IHM::getInstanceOf().printData(buffer1, 11, 1);
162
            buffer1 = "Gyro: "+std::to_string(drone1.highres_imu.xgyro)+" "+std::to_string(drone1.highres_imu.ygyro)+" "+std::to_string(drone1.highres_imu.zgyro);
163
            //Display_IHM::getInstanceOf().printData(buffer1, 12, 1);
164
            buffer1 = "Mag: "+std::to_string(drone1.highres_imu.xmag)+" "+std::to_string(drone1.highres_imu.ymag)+" "+std::to_string(drone1.highres_imu.zmag);
165
166
            //Display_IHM::getInstanceOf().printData(buffer1, 13, 1);

167
168
169
170
171
172
173
174
175
            blc_highres_imu.floats[0] = drone1.highres_imu.xacc;
            blc_highres_imu.floats[1] = drone1.highres_imu.yacc;
            blc_highres_imu.floats[2] = drone1.highres_imu.zacc;
            blc_highres_imu.floats[3] = drone1.highres_imu.xgyro;
            blc_highres_imu.floats[4] = drone1.highres_imu.ygyro;
            blc_highres_imu.floats[5] = drone1.highres_imu.zgyro;
            blc_highres_imu.floats[6] = drone1.highres_imu.xmag;
            blc_highres_imu.floats[7] = drone1.highres_imu.ymag;
            blc_highres_imu.floats[8] = drone1.highres_imu.zmag;
176
177
178
179
180
181
            break;
        }

        //GPS
        case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
        {
182
            mavlink_msg_local_position_ned_decode(&message, &drone1.local_position_ned);
183

184
            buffer1 = "Pos_coord: "+std::to_string(drone1.local_position_ned.x)+" "+std::to_string(drone1.local_position_ned.y)+" "+std::to_string(drone1.local_position_ned.z);
185
            //Display_IHM::getInstanceOf().printData(buffer1, 14, 1);
186
            buffer1 = "Pos_speed: "+std::to_string(drone1.local_position_ned.vx)+" "+std::to_string(drone1.local_position_ned.vy)+" "+std::to_string(drone1.local_position_ned.vz);
187
188
189
190
191
            //Display_IHM::getInstanceOf().printData(buffer1, 15, 1);
            break;
        }
        case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
        {
192
            mavlink_msg_position_target_local_ned_decode(&message, &drone1.position_target_local_ned);
193

194
            /*buffer1 = "Pos_coord_t: "+std::to_string(drone1.position_target_local_ned.x)+" "+std::to_string(drone1.position_target_local_ned.y)+" "+std::to_string(drone1.position_target_local_ned.z);
195
            Display_IHM::getInstanceOf().printData(buffer1, 10, 1);
196
            buffer1 = "Pos_speed_t: "+std::to_string(drone1.position_target_local_ned.vx)+" "+std::to_string(drone1.position_target_local_ned.vy)+" "+std::to_string(drone1.position_target_local_ned.vz);
197
198
199
200
201
202
            Display_IHM::getInstanceOf().printData(buffer1, 11, 1);*/
            break;
        }

        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
        {
203
204
            /*mavlink_msg_global_position_int_decode(&message, &drone1.global_position_int);
            buffer1 = "GPS: "+std::to_string(drone1.global_position_int.lat)+" "+std::to_string(drone1.global_position_int.lon)+" "+std::to_string(drone1.global_position_int.alt);
205
206
207
208
209
210
211
            Display_IHM::getInstanceOf().printData(buffer1, 12, 1);*/
            break;
        }

        //Attitude function
        case MAVLINK_MSG_ID_ATTITUDE:
        {
212
            mavlink_msg_attitude_decode(&message, &drone1.attitude);
213
            
214
            /*buffer1 = "Attitude_t: "+std::to_string(drone1.attitude.time_boot_ms);
215
            Display_IHM::getInstanceOf().printData(buffer1, 13, 1);
216
            buffer1 = "Attitude_p: "+std::to_string(drone1.attitude.roll)+" "+std::to_string(drone1.attitude.pitch)+" "+std::to_string(drone1.attitude.yaw);
217
            Display_IHM::getInstanceOf().printData(buffer1, 14, 1);
218
            buffer1 = "Attitude_s: "+std::to_string(drone1.attitude.rollspeed)+" "+std::to_string(drone1.attitude.pitchspeed)+" "+std::to_string(drone1.attitude.yawspeed);
219
220
221
222
223
224
            Display_IHM::getInstanceOf().printData(buffer1, 15, 1);*/
            
            break;
        }
        case MAVLINK_MSG_ID_ATTITUDE_TARGET:
        {
225
            mavlink_msg_attitude_target_decode(&message, &drone1.attitude_target);
226

227
            /*buffer1 = "Attitude_target: "+std::to_string(drone1.attitude_target.time_boot_ms);
228
            Display_IHM::getInstanceOf().printData(buffer1, 16, 1);
229
            buffer1 = "Attitude_target_q: "+std::to_string(drone1.attitude_target.q[0])+" "+std::to_string(drone1.attitude_target.q[1])+" "+std::to_string(drone1.attitude_target.q[2])+" "+std::to_string(drone1.attitude_target.q[3]);
230
            Display_IHM::getInstanceOf().printData(buffer1, 17, 1);
231
            buffer1 = "Attitude_tar_r: "+std::to_string(drone1.attitude_target.body_roll_rate)+" "+std::to_string(drone1.attitude_target.body_pitch_rate)+" "+std::to_string(drone1.attitude_target.body_yaw_rate);
232
            Display_IHM::getInstanceOf().printData(buffer1, 18, 1);
233
            buffer1 = "Attitude_tar_m: "+std::to_string(drone1.attitude_target.type_mask);
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
            Display_IHM::getInstanceOf().printData(buffer1, 19, 1);*/
            break;
        }

        default:
        {
            //printf("Warning, did not handle message id %i\n",message.msgid);
            break;
        }


    }

} 


uint64_t Serial_Port_ReadingThread::get_time_usec(){
	static struct timeval _time_stamp;
	gettimeofday(&_time_stamp, NULL);
	return _time_stamp.tv_sec*1000000 + _time_stamp.tv_usec;
}

int Serial_Port_ReadingThread::testAck(mavlink_command_ack_t *ack, std::string message){
    std::string buffer1="-> Ack-";
    buffer1+=message;

    if (ack->result == MAV_RESULT_ACCEPTED) {
        buffer1+="-succes";
        //Display_IHM::getInstanceOf().printLog(buffer1);
        return 0;
    } else {
        buffer1+="-fail";
        //Display_IHM::getInstanceOf().printLog(buffer1);
        return 1;
    }
}

void Serial_Port_ReadingThread::handle_command_ack(mavlink_command_ack_t *ack)
{
    switch (ack->command) {
        case MAV_CMD_COMPONENT_ARM_DISARM:
            if(testAck(ack, "Arm_desarm") == 1){ //if command is succeed
276
277
278
279
                /*if(drone1.motors == ARM){
                    drone1.motors = UNARM;
                }else if(drone1.motors == UNARM){
                    drone1.motors = ARM;
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
                }*/
            }
            //motors
            break;
        case MAV_CMD_NAV_GUIDED_ENABLE:
            testAck(ack, "navGuided");
            break;
        case MAVLINK_MSG_ID_PLAY_TUNE:
            testAck(ack, "Tone");
            break;
        case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
            testAck(ack, "Attitude");
            break;
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            testAck(ack, "Manual control");
            break;
        default:
            testAck(ack, "Unknow");
            break;
    }
    ////Display_IHM::getInstanceOf().displayDroneState(drone1);
    
}