Skip to content

Commit

Permalink
clanf format
Browse files Browse the repository at this point in the history
  • Loading branch information
facontidavide committed Dec 11, 2023
1 parent 86d103d commit 43c4010
Show file tree
Hide file tree
Showing 88 changed files with 15,733 additions and 15,137 deletions.
72 changes: 36 additions & 36 deletions plotjuggler_base/include/PlotJuggler/special_messages.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ struct Time

double toSec() const
{
return double(sec) + double(nanosec)*1e-9;
return double(sec) + double(nanosec)*1e-9;
}
};

Expand Down Expand Up @@ -61,11 +61,11 @@ struct Vector3

struct Point
{
double x;
double y;
double z;
double x;
double y;
double z;

static const char* id() { return "geometry_msgs/Point"; }
static const char* id() { return "geometry_msgs/Point"; }
};

struct Quaternion
Expand Down Expand Up @@ -97,51 +97,51 @@ struct Transform

struct TransformStamped
{
Header header;
std::string child_frame_id;
Transform transform;
Header header;
std::string child_frame_id;
Transform transform;

static const char* id() { return "geometry_msgs/TransformStamped"; }
static const char* id() { return "geometry_msgs/TransformStamped"; }
};

struct Pose
{
Vector3 position;
Quaternion orientation;
Vector3 position;
Quaternion orientation;

static const char* id() { return "geometry_msgs/Pose"; }
static const char* id() { return "geometry_msgs/Pose"; }
};

struct PoseStamped
{
Header header;
Pose pose;
Header header;
Pose pose;

static const char* id() { return "geometry_msgs/PoseStamped"; }
static const char* id() { return "geometry_msgs/PoseStamped"; }
};

struct PoseWithCovariance
{
Pose pose;
std::array<double, 36> covariance;
Pose pose;
std::array<double, 36> covariance;

static const char* id() { return "geometry_msgs/PoseWithCovariance"; }
static const char* id() { return "geometry_msgs/PoseWithCovariance"; }
};

struct Twist
{
Vector3 linear;
Vector3 angular;
Vector3 linear;
Vector3 angular;

static const char* id() { return "geometry_msgs/Twist"; }
static const char* id() { return "geometry_msgs/Twist"; }
};

struct TwistWithCovariance
{
Twist twist;
std::array<double, 36> covariance;
Twist twist;
std::array<double, 36> covariance;

static const char* id() { return "geometry_msgs/TwistWithCovariance"; }
static const char* id() { return "geometry_msgs/TwistWithCovariance"; }
};

struct TFMessage
Expand All @@ -154,24 +154,24 @@ struct TFMessage

struct Imu
{
Header header;
Quaternion orientation;
std::array<double, 9> orientation_covariance;
Vector3 angular_velocity;
std::array<double, 9> angular_velocity_covariance;
Vector3 linear_acceleration;
std::array<double, 9> linear_acceleration_covariance;
Header header;
Quaternion orientation;
std::array<double, 9> orientation_covariance;
Vector3 angular_velocity;
std::array<double, 9> angular_velocity_covariance;
Vector3 linear_acceleration;
std::array<double, 9> linear_acceleration_covariance;

static const char* id() { return "sensor_msgs/Imu"; }
static const char* id() { return "sensor_msgs/Imu"; }
};
//--------------------
struct Odometry
{
Header header;
PoseWithCovariance pose;
TwistWithCovariance twist;
Header header;
PoseWithCovariance pose;
TwistWithCovariance twist;

static const char* id() { return "nav_msgs/Odometry"; }
static const char* id() { return "nav_msgs/Odometry"; }
};

//--------------------
Expand Down
Loading

0 comments on commit 43c4010

Please sign in to comment.