Skip to content

Commit

Permalink
la: add a timestamp, version and duration
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Aug 28, 2015
1 parent d8d1957 commit 3934c9c
Show file tree
Hide file tree
Showing 7 changed files with 19 additions and 5 deletions.
3 changes: 3 additions & 0 deletions analyze.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,6 +350,9 @@ void Analyze::end_of_log(uint32_t packet_count) {
}

Json::Value root;
root["format-version"] = "0.1";
root["timestamp"] = (Json::UInt64)start_time;
root["duration"] = (Json::UInt64)(now() - start_time);

results_json(root);

Expand Down
5 changes: 5 additions & 0 deletions analyze.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include "analyzer.h"
#include "analyzervehicle_copter.h"

#include "analyzer_util.h"

class Analyze : public MAVLink_Message_Handler {

public:
Expand All @@ -14,6 +16,7 @@ class Analyze : public MAVLink_Message_Handler {
_output_style(OUTPUT_JSON),
next_analyzer(0)
{
start_time = now();
}
void instantiate_analyzers(INIReader *config);

Expand All @@ -28,6 +31,8 @@ class Analyze : public MAVLink_Message_Handler {
void set_output_style(output_style_option option) { _output_style = option;}

private:
uint64_t start_time;

AnalyzerVehicle::Base *vehicle;

output_style_option _output_style;
Expand Down
1 change: 0 additions & 1 deletion analyzer_attitude_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ class Analyzer_Attitude_Control : public Analyzer {
void handle_decoded_message(uint64_t T, mavlink_nav_controller_output_t &param);
void handle_decoded_message(uint64_t T, mavlink_attitude_t &msg);

bool is_zero(double x) { return x < 0.00001; } // FIXME
void evaluate(uint64_t T);

private:
Expand Down
4 changes: 2 additions & 2 deletions analyzer_notcrashed.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ class Analyzer_NotCrashed : public Analyzer {
public:
Analyzer_NotCrashed(int fd, struct sockaddr_in &sa, AnalyzerVehicle::Base *&vehicle) :
Analyzer(fd, sa, vehicle),
seen_packets_attitude(false),
notcrashed_results_offset(0)
notcrashed_results_offset(0),
seen_packets_attitude(false)
{ }

const uint16_t servo_output_threshold = 1250;
Expand Down
7 changes: 7 additions & 0 deletions analyzer_util.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "analyzer_util.h"
#include <sys/time.h>

void format_timestamp(char *buf, const uint8_t buflen, const uint64_t T)
{
Expand All @@ -7,3 +8,9 @@ void format_timestamp(char *buf, const uint8_t buflen, const uint64_t T)
tmp = localtime(&t);
::strftime(buf, buflen, "%Y%m%d%H%M%S", tmp);
}

uint64_t now() {
struct timeval tv;
gettimeofday(&tv,NULL);
return tv.tv_sec*(uint64_t)1000000 + tv.tv_usec;
}
2 changes: 2 additions & 0 deletions analyzer_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,6 @@ std::string string_format( const char* format, Args ... args )

void format_timestamp(char *buf, uint8_t buflen, uint64_t T);

uint64_t now();

#endif
2 changes: 0 additions & 2 deletions mavlink_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@

#include <dirent.h>

#define streq(a, b) (!strcmp(a, b))

static bool sighup_received = false;
void sighup_handler(int signal)
{
Expand Down

0 comments on commit 3934c9c

Please sign in to comment.