APM:Libraries
SIM_last_letter.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simulator connector for ardupilot version of last_letter
17 */
18 
19 #include "SIM_last_letter.h"
20 
21 #include <fcntl.h>
22 #include <stdio.h>
23 #include <sys/stat.h>
24 #include <sys/types.h>
25 
26 #include <AP_HAL/AP_HAL.h>
27 
28 extern const AP_HAL::HAL& hal;
29 
30 namespace SITL {
31 
32 last_letter::last_letter(const char *home_str, const char *_frame_str) :
33  Aircraft(home_str, _frame_str),
34  last_timestamp_us(0),
35  sock(true)
36 {
37  // try to bind to a specific port so that if we restart ArduPilot
38  // last_letter keeps sending us packets. Not strictly necessary but
39  // useful for debugging
40  sock.bind("127.0.0.1", fdm_port+1);
41 
42  sock.reuseaddress();
43  sock.set_blocking(false);
44 
46 }
47 
48 /*
49  start last_letter child
50  */
52 {
53  pid_t child_pid = fork();
54  if (child_pid == 0) {
55  // in child
56  close(0);
57  open("/dev/null", O_RDONLY|O_CLOEXEC);
58  for (uint8_t i=3; i<100; i++) {
59  close(i);
60  }
61  int ret = execlp("roslaunch",
62  "roslaunch",
63  "last_letter",
64  "gazebo.launch",
65  "ArduPlane:=true",
66  nullptr);
67  if (ret != 0) {
68  perror("roslaunch");
69  }
70  exit(1);
71  }
72 }
73 
74 /*
75  send servos
76 */
77 void last_letter::send_servos(const struct sitl_input &input)
78 {
79  servo_packet pkt;
80  memcpy(pkt.servos, input.servos, sizeof(pkt.servos));
81  sock.sendto(&pkt, sizeof(pkt), "127.0.0.1", fdm_port);
82 }
83 
84 /*
85  receive an update from the FDM
86  This is a blocking function
87  */
88 void last_letter::recv_fdm(const struct sitl_input &input)
89 {
90  fdm_packet pkt;
91 
92  /*
93  we re-send the servo packet every 0.1 seconds until we get a
94  reply. This allows us to cope with some packet loss to the FDM
95  */
96  while (sock.recv(&pkt, sizeof(pkt), 100) != sizeof(pkt)) {
97  send_servos(input);
98  }
99 
100  accel_body = Vector3f(pkt.xAccel, pkt.yAccel, pkt.zAccel);
101  gyro = Vector3f(pkt.rollRate, pkt.pitchRate, pkt.yawRate);
102  velocity_ef = Vector3f(pkt.speedN, pkt.speedE, pkt.speedD);
103  location.lat = pkt.latitude * 1.0e7;
104  location.lng = pkt.longitude * 1.0e7;
105  location.alt = pkt.altitude*1.0e2;
106  dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
107 
108  airspeed = pkt.airspeed;
109  airspeed_pitot = pkt.airspeed;
110 
111 
112  // auto-adjust to last_letter frame rate
113  uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us;
114  time_now_us += deltat_us;
115 
116  if (deltat_us < 1.0e4 && deltat_us > 0) {
117  adjust_frame_time(1.0e6/deltat_us);
118  }
120 }
121 
122 /*
123  update the last_letter simulation by one time step
124  */
125 void last_letter::update(const struct sitl_input &input)
126 {
127  send_servos(input);
128  recv_fdm(input);
129  sync_frame_time();
130 
131  update_position();
132  time_advance();
133  // update magnetic field
135 }
136 
137 } // namespace SITL
Vector3f accel_body
Definition: SIM_Aircraft.h:142
void sync_frame_time(void)
Vector3< float > Vector3f
Definition: vector3.h:246
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void recv_fdm(const struct sitl_input &input)
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
Location location
Definition: SIM_Aircraft.h:127
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
void start_last_letter(void)
void perror(const char *s)
POSIX perror() - convert POSIX errno to text with user message.
Definition: posix.c:1827
float airspeed_pitot
Definition: SIM_Aircraft.h:144
void send_servos(const struct sitl_input &input)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
uint64_t last_timestamp_us
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
void update(const struct sitl_input &input)
void adjust_frame_time(float rate)
void update_mag_field_bf(void)
void update_position(void)
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
static const uint16_t fdm_port
last_letter(const char *home_str, const char *frame_str)