From 95236c379a3b0a551f5ac26387356ecad0a82d60 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 13 Jun 2013 06:51:09 +0400 Subject: sdlog2: ARSP (attitude rates setpoint) message added, attitude rates added to ATT message --- src/modules/sdlog2/sdlog2.c | 25 ++++++++++++++++++++++++- src/modules/sdlog2/sdlog2_messages.h | 14 +++++++++++++- 2 files changed, 37 insertions(+), 2 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index a14bd6f80..ca6ab5934 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -64,6 +64,7 @@ #include #include #include +#include #include #include #include @@ -612,7 +613,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 15; + const ssize_t fdsc = 16; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -627,6 +628,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct sensor_combined_s sensor; struct vehicle_attitude_s att; struct vehicle_attitude_setpoint_s att_sp; + struct vehicle_rates_setpoint_s rates_sp; struct actuator_outputs_s act_outputs; struct actuator_controls_s act_controls; struct actuator_controls_effective_s act_controls_effective; @@ -648,6 +650,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int sensor_sub; int att_sub; int att_sp_sub; + int rates_sp_sub; int act_outputs_sub; int act_controls_sub; int act_controls_effective_sub; @@ -677,6 +680,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_STAT_s log_STAT; struct log_RC_s log_RC; struct log_OUT0_s log_OUT0; + struct log_ARSP_s log_ARSP; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -720,6 +724,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; + /* --- RATES SETPOINT --- */ + subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint)); + fds[fdsc_count].fd = subs.rates_sp_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* --- ACTUATOR OUTPUTS --- */ subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS); fds[fdsc_count].fd = subs.act_outputs_sub; @@ -953,6 +963,9 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATT.roll = buf.att.roll; log_msg.body.log_ATT.pitch = buf.att.pitch; log_msg.body.log_ATT.yaw = buf.att.yaw; + log_msg.body.log_ATT.roll_rate = buf.att.rollspeed; + log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed; + log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed; LOGBUFFER_WRITE_AND_COUNT(ATT); } @@ -966,6 +979,16 @@ int sdlog2_thread_main(int argc, char *argv[]) LOGBUFFER_WRITE_AND_COUNT(ATSP); } + /* --- RATES SETPOINT --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp); + log_msg.msg_type = LOG_ARSP_MSG; + log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll; + log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch; + log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw; + LOGBUFFER_WRITE_AND_COUNT(ARSP); + } + /* --- ACTUATOR OUTPUTS --- */ if (fds[ifds++].revents & POLLIN) { orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs); diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 40763ee1e..48322e0b6 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -60,6 +60,9 @@ struct log_ATT_s { float roll; float pitch; float yaw; + float roll_rate; + float pitch_rate; + float yaw_rate; }; /* --- ATSP - ATTITUDE SET POINT --- */ @@ -167,13 +170,21 @@ struct log_RC_s { struct log_OUT0_s { float output[8]; }; + +/* --- ARSP - ATTITUDE RATE SET POINT --- */ +#define LOG_ARSP_MSG 13 +struct log_ARSP_s { + float roll_rate_sp; + float pitch_rate_sp; + float yaw_rate_sp; +}; #pragma pack(pop) /* construct list of all message formats */ static const struct log_format_s log_formats[] = { LOG_FORMAT(TIME, "Q", "StartTime"), - LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"), + LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"), LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), @@ -184,6 +195,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"), LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"), LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"), + LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); -- cgit v1.2.3 From 138ce117ab0a9b95f473f34ce8644fa6456b32a6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Jun 2013 17:20:07 +0400 Subject: ATSP.ThrustSP added --- src/modules/sdlog2/sdlog2.c | 1 + src/modules/sdlog2/sdlog2_messages.h | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index ca6ab5934..f67cfad87 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -976,6 +976,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body; log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body; log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body; + log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust; LOGBUFFER_WRITE_AND_COUNT(ATSP); } diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 48322e0b6..fc5687988 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -71,6 +71,7 @@ struct log_ATSP_s { float roll_sp; float pitch_sp; float yaw_sp; + float thrust_sp; }; /* --- IMU - IMU SENSORS --- */ @@ -185,7 +186,7 @@ struct log_ARSP_s { static const struct log_format_s log_formats[] = { LOG_FORMAT(TIME, "Q", "StartTime"), LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"), - LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), + LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"), -- cgit v1.2.3 From d9f30858c88f6613808d1781ce06058e88e40fa9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Jun 2013 14:46:18 +0400 Subject: sdlog2 messages ID fix --- src/modules/sdlog2/sdlog2_messages.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src') diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index efb999a50..7f7bf6053 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -180,7 +180,7 @@ struct log_AIRS_s { }; /* --- ARSP - ATTITUDE RATE SET POINT --- */ -#define LOG_ARSP_MSG 13 +#define LOG_ARSP_MSG 14 struct log_ARSP_s { float roll_rate_sp; float pitch_rate_sp; -- cgit v1.2.3 From a11895ac43b4e345ebd04d9999f386bc1408b98e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Jun 2013 16:06:35 +0400 Subject: Critical bug fixed, cleanup --- src/modules/sdlog2/logbuffer.c | 2 +- src/modules/sdlog2/sdlog2.c | 80 ++++++++++++++++++------------------------ 2 files changed, 35 insertions(+), 47 deletions(-) (limited to 'src') diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index 8aaafaf31..2e1e4fd4d 100644 --- a/src/modules/sdlog2/logbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -121,7 +121,7 @@ int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part) } else { // read pointer is after write pointer, read bytes from read_ptr to end of the buffer n = lb->size - lb->read_ptr; - *is_part = true; + *is_part = lb->write_ptr > 0; } *ptr = &(lb->data[lb->read_ptr]); diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 178986f61..6715b57f5 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -114,35 +114,34 @@ static const int MAX_WRITE_CHUNK = 512; static const int MIN_BYTES_TO_WRITE = 512; static const char *mountpoint = "/fs/microsd"; -int log_file = -1; -int mavlink_fd = -1; +static int mavlink_fd = -1; struct logbuffer_s lb; /* mutex / condition to synchronize threads */ -pthread_mutex_t logbuffer_mutex; -pthread_cond_t logbuffer_cond; +static pthread_mutex_t logbuffer_mutex; +static pthread_cond_t logbuffer_cond; -char folder_path[64]; +static char folder_path[64]; /* statistics counters */ -unsigned long log_bytes_written = 0; -uint64_t start_time = 0; -unsigned long log_msgs_written = 0; -unsigned long log_msgs_skipped = 0; +static unsigned long log_bytes_written = 0; +static uint64_t start_time = 0; +static unsigned long log_msgs_written = 0; +static unsigned long log_msgs_skipped = 0; /* current state of logging */ -bool logging_enabled = false; +static bool logging_enabled = false; /* enable logging on start (-e option) */ -bool log_on_start = false; +static bool log_on_start = false; /* enable logging when armed (-a option) */ -bool log_when_armed = false; +static bool log_when_armed = false; /* delay = 1 / rate (rate defined by -r option) */ -useconds_t sleep_delay = 0; +static useconds_t sleep_delay = 0; /* helper flag to track system state changes */ -bool flag_system_armed = false; +static bool flag_system_armed = false; -pthread_t logwriter_pthread = 0; +static pthread_t logwriter_pthread = 0; /** * Log buffer writing thread. Open and close file here. @@ -172,17 +171,17 @@ static void sdlog2_status(void); /** * Start logging: create new file and start log writer thread. */ -void sdlog2_start_log(); +static void sdlog2_start_log(void); /** * Stop logging: stop log writer thread and close log file. */ -void sdlog2_stop_log(); +static void sdlog2_stop_log(void); /** * Write a header to log file: list of message formats. */ -void write_formats(int fd); +static void write_formats(int fd); static bool file_exist(const char *filename); @@ -196,12 +195,12 @@ static void handle_status(struct vehicle_status_s *cmd); /** * Create folder for current logging session. Store folder name in 'log_folder'. */ -static int create_logfolder(); +static int create_logfolder(void); /** * Select first free log file name and open it. */ -static int open_logfile(); +static int open_logfile(void); static void sdlog2_usage(const char *reason) @@ -286,22 +285,6 @@ int create_logfolder() if (mkdir_ret == 0) { /* folder does not exist, success */ - - /* copy parser script file */ - // TODO - /* - char mfile_out[100]; - sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber); - int ret = file_copy(mfile_in, mfile_out); - - if (!ret) { - warnx("copied m file to %s", mfile_out); - - } else { - warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out); - } - */ - break; } else if (mkdir_ret == -1) { @@ -403,6 +386,11 @@ static void *logwriter_thread(void *arg) /* only get pointer to thread-safe data, do heavy I/O a few lines down */ int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part); +#ifdef SDLOG2_DEBUG + int rp = logbuf->read_ptr; + int wp = logbuf->write_ptr; +#endif + /* continue */ pthread_mutex_unlock(&logbuffer_mutex); @@ -419,7 +407,7 @@ static void *logwriter_thread(void *arg) should_wait = (n == available) && !is_part; #ifdef SDLOG2_DEBUG - printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait); + printf("write %i %i of %i rp=%i wp=%i, is_part=%i, should_wait=%i\n", log_bytes_written, n, available, rp, wp, (int)is_part, (int)should_wait); #endif if (n < 0) { @@ -432,14 +420,14 @@ static void *logwriter_thread(void *arg) } } else { + n = 0; should_wait = true; } - if (poll_count % 10 == 0) { + if (++poll_count == 10) { fsync(log_file); + poll_count = 0; } - - poll_count++; } fsync(log_file); @@ -608,12 +596,9 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "can't allocate log buffer, exiting."); } - /* file descriptors to wait for */ - struct pollfd fds_control[2]; - /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 16; + const ssize_t fdsc = 17; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -901,7 +886,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_GPS.epv = buf.gps_pos.epv_m; log_msg.body.log_GPS.lat = buf.gps_pos.lat; log_msg.body.log_GPS.lon = buf.gps_pos.lon; - log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001; + log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001f; log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s; log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s; log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s; @@ -1087,10 +1072,13 @@ int sdlog2_thread_main(int argc, char *argv[]) LOGBUFFER_WRITE_AND_COUNT(AIRS); } +#ifdef SDLOG2_DEBUG + printf("fill rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb)); +#endif /* signal the other thread new data, but not yet unlock */ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { #ifdef SDLOG2_DEBUG - printf("signal %i", logbuffer_count(&lb)); + printf("signal rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb)); #endif /* only request write if several packets can be written at once */ pthread_cond_signal(&logbuffer_cond); -- cgit v1.2.3