Skip to content
This repository has been archived by the owner on Jul 1, 2022. It is now read-only.

Commit

Permalink
Release 1.8.0
Browse files Browse the repository at this point in the history
  • Loading branch information
waltjohnson committed Jan 31, 2020
1 parent 7b49152 commit 2d5b214
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 7 deletions.
29 changes: 23 additions & 6 deletions include/inertial_sense.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,16 @@
#include "std_msgs/Header.h"
#include "geometry_msgs/Vector3Stamped.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "diagnostic_msgs/DiagnosticArray.h"
#include <tf/transform_broadcaster.h>
//#include "geometry/xform.h"

# define GPS_UNIX_OFFSET 315964800 // GPS time started on 6/1/1980 while UNIX time started 1/1/1970 this is the difference between those in seconds
# define LEAP_SECONDS 18 // GPS time does not have leap seconds, UNIX does (as of 1/1/2017 - next one is probably in 2020 sometime unless there is some crazy earthquake or nuclear blast)
# define UNIX_TO_GPS_OFFSET (GPS_UNIX_OFFSET - LEAP_SECONDS)

#define SET_CALLBACK(DID, __type, __cb_fun) \
IS_.BroadcastBinaryData(DID, 1, \
#define SET_CALLBACK(DID, __type, __cb_fun, __periodmultiple) \
IS_.BroadcastBinaryData(DID, __periodmultiple, \
[this](InertialSense*i, p_data_t* data, int pHandle)\
{ \
/* ROS_INFO("Got message %d", DID);*/\
Expand Down Expand Up @@ -71,7 +73,7 @@ class InertialSenseROS //: SerialListener
void start_log();

template<typename T> void set_vector_flash_config(std::string param_name, uint32_t size, uint32_t offset);
template<typename T> void set_flash_config(std::string param_name, uint32_t offset, T def);
template<typename T> void set_flash_config(std::string param_name, uint32_t offset, T def) __attribute__ ((optimize(0)));
void get_flash_config();
void reset_device();
void flash_config_callback(const nvm_flash_cfg_t* const msg);
Expand All @@ -96,6 +98,16 @@ class InertialSenseROS //: SerialListener
void INS2_callback(const ins_2_t* const msg);
// void INS_variance_callback(const inl2_variance_t* const msg);

tf::TransformBroadcaster br;
bool publishTf;
tf::Transform transform;
int LTCF;
enum
{
NED,
ENU
}ltcf;

ros_stream_t IMU_;
void IMU_callback(const dual_imu_t* const msg);

Expand Down Expand Up @@ -128,6 +140,11 @@ class InertialSenseROS //: SerialListener
ros::Publisher strobe_pub_;
void strobe_in_time_callback(const strobe_in_time_t * const msg);

ros_stream_t diagnostics_;
void diagnostics_callback(const ros::TimerEvent& event);
ros::Timer diagnostics_timer_;
float diagnostic_ar_ratio_, diagnostic_differential_age_, diagnostic_heading_base_to_rover_;

ros::ServiceServer mag_cal_srv_;
ros::ServiceServer multi_mag_cal_srv_;
ros::ServiceServer firmware_update_srv_;
Expand Down Expand Up @@ -190,9 +207,10 @@ class InertialSenseROS //: SerialListener

// Data to hold on to in between callbacks
double lla_[3];
double ecef_[3];
sensor_msgs::Imu imu1_msg, imu2_msg;
nav_msgs::Odometry odom_msg;
inertial_sense::GPS gps_msg;
inertial_sense::GPS gps_msg;
geometry_msgs::Vector3Stamped gps_velEcef;
inertial_sense::GPSInfo gps_info_msg;

Expand All @@ -201,5 +219,4 @@ class InertialSenseROS //: SerialListener

// Connection to the uINS
InertialSense IS_;
};

};
2 changes: 1 addition & 1 deletion src/inertial_sense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void InertialSenseROS::configure_data_streams()
{
mag_.pub = nh_.advertise<sensor_msgs::MagneticField>("mag", 1);
// mag_.pub2 = nh_.advertise<sensor_msgs::MagneticField>("mag2", 1);
SET_CALLBACK(DID_MAGNETOMETER_1, magnetometer_t, mag_callback,1);
SET_CALLBACK(DID_MAGNETOMETER, magnetometer_t, mag_callback,1);
}

// Set up the barometer ROS stream
Expand Down

0 comments on commit 2d5b214

Please sign in to comment.