Skip to content

Commit

Permalink
Merge pull request #21 from samkys/cleanup
Browse files Browse the repository at this point in the history
Cleanup
  • Loading branch information
tonybaltovski authored Jul 11, 2019
2 parents 87ecdb3 + 43ae385 commit db3f119
Show file tree
Hide file tree
Showing 5 changed files with 2,842 additions and 2,203 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ project(microstrain_mips)
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roslint
message_generation
geometry_msgs
nav_msgs
Expand Down Expand Up @@ -479,3 +480,7 @@ install(DIRECTORY launch config

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

## Run roslint on only the node files for now
# TODO: Add more files as needed
roslint_cpp(src/microstrain_3dm.cpp src/microstrain_3dm_node.cpp)
26 changes: 15 additions & 11 deletions include/microstrain_mips/microstrain_3dm.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,15 @@ along with Foobar. If not, see <http://www.gnu.org/licenses/>.
#define _MICROSTRAIN_3DM_H

// Tell compiler that the following MIP SDI are C functions
extern "C" {
#include "mip_sdk.h"
#include "byteswap_utilities.h"
#include "mip_gx4_imu.h"
#include "mip_gx4_45.h"
#include "mip_gx4_25.h"
#include "mip_sdk_3dm.h"
#include "GX4-45_Test.h"
extern "C"
{
#include "mip_sdk.h"
#include "byteswap_utilities.h"
#include "mip_gx4_imu.h"
#include "mip_gx4_45.h"
#include "mip_gx4_25.h"
#include "mip_sdk_3dm.h"
#include "GX4-45_Test.h"
}

#include <cstdio>
Expand Down Expand Up @@ -82,8 +83,8 @@ extern "C" {
#include "microstrain_mips/SetMagDipAdaptiveVals.h"


#define MIP_SDK_GX4_45_IMU_STANDARD_MODE 0x01
#define MIP_SDK_GX4_45_IMU_DIRECT_MODE 0x02
#define MIP_SDK_GX4_45_IMU_STANDARD_MODE 0x01
#define MIP_SDK_GX4_45_IMU_DIRECT_MODE 0x02

#define NUM_COMMAND_LINE_ARGUMENTS 3

Expand Down Expand Up @@ -241,7 +242,7 @@ namespace Microstrain
private:
//! @brief Reset KF service callback
bool reset_callback(std_srvs::Empty::Request &req,
std_srvs::Empty::Response &resp);
std_srvs::Empty::Response &resp);
//! @brief Convience for printing packet stats
void print_packet_stats();

Expand Down Expand Up @@ -309,6 +310,9 @@ namespace Microstrain
bool publish_imu_;
bool publish_odom_;
bool publish_bias_;
std::vector<double> imu_linear_cov_;
std::vector<double> imu_angular_cov_;
std::vector<double> imu_orientation_cov_;

//Device Flags
bool GX5_15;
Expand Down
5 changes: 5 additions & 0 deletions launch/microstrain.launch
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,11 @@
<!-- Declination source 1=None, 2=magnetic, 3=manual -->
<param name="declination_source" value="2" type="int" />
<param name="declination" value="0.23" type="double" />
<!-- Static IMU message covariance values -->
<!-- Since internally these are std::vector we need to use the rosparam tags -->
<rosparam param="imu_orientation_cov"> [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01]</rosparam>
<rosparam param="imu_linear_cov"> [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01]</rosparam>
<rosparam param="imu_angular_cov"> [0.01, 0, 0, 0, 0.01, 0, 0, 0, 0.01]</rosparam>

<!-- GPS Settings -45 and -35 Only -->
<param name="gps_rate" value="4" type="int" />
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>nav_msgs</depend>

<build_depend>message_generation</build_depend>
<build_depend>roslint</build_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>diagnostic_updater</exec_depend>
<exec_depend>diagnostic_aggregator</exec_depend>
Expand Down
Loading

0 comments on commit db3f119

Please sign in to comment.