Skip to content

Commit

Permalink
Merge pull request #3 from ironmig/dev
Browse files Browse the repository at this point in the history
Replace uf_common with mil_msgs for great merge compatibility
  • Loading branch information
DSsoto authored Apr 11, 2017
2 parents b23dc5d + e5df149 commit 299eb06
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 18 deletions.
4 changes: 2 additions & 2 deletions odom_estimator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 2.8.3)
project(odom_estimator)
# Load catkin and all dependencies required for this package
# TODO: remove all from COMPONENTS that are not catkin packages.
find_package(catkin REQUIRED COMPONENTS roscpp pluginlib sensor_msgs eigen_conversions geometry_msgs tf nodelet tf_conversions std_msgs message_generation cmake_modules uf_common)
find_package(catkin REQUIRED COMPONENTS roscpp pluginlib sensor_msgs eigen_conversions geometry_msgs tf nodelet tf_conversions std_msgs message_generation cmake_modules mil_msgs)
# CATKIN_MIGRATION: removed during catkin migration
# cmake_minimum_required(VERSION 2.4.6)

Expand Down Expand Up @@ -55,7 +55,7 @@ generate_messages(
# TODO: fill in what other packages will need to use this package
catkin_package(
DEPENDS Eigen # TODO
CATKIN_DEPENDS roscpp pluginlib sensor_msgs eigen_conversions geometry_msgs tf uf_common nodelet tf_conversions std_msgs message_runtime
CATKIN_DEPENDS roscpp pluginlib sensor_msgs eigen_conversions geometry_msgs tf mil_msgs nodelet tf_conversions std_msgs message_runtime
INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS} include# TODO include
LIBRARIES # TODO
)
Expand Down
4 changes: 2 additions & 2 deletions odom_estimator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
<build_depend>std_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>cmake_modules</build_depend>
<build_depend>uf_common</build_depend>
<build_depend>mil_msgs</build_depend>

<!-- Dependencies needed after this package is compiled. -->
<run_depend>roscpp</run_depend>
Expand All @@ -39,7 +39,7 @@
<run_depend>tf_conversions</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>uf_common</run_depend>
<run_depend>mil_msgs</run_depend>

<!-- Dependencies needed only for running tests. -->
<!-- <test_depend>roscpp</test_depend> -->
Expand Down
28 changes: 14 additions & 14 deletions odom_estimator/src/nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
#include <eigen_conversions/eigen_msg.h>
#include <tf_conversions/tf_eigen.h>

#include <uf_common/VelocityMeasurements.h>
#include <uf_common/Float64Stamped.h>
#include <mil_msgs/VelocityMeasurements.h>
#include <mil_msgs/DepthStamped.h>

#include <odom_estimator/Info.h>
#include <odom_estimator/SetIgnoreMagnetometer.h>
Expand Down Expand Up @@ -263,8 +263,8 @@ class NodeImpl {
*state);
}

void got_dvl(const uf_common::VelocityMeasurementsConstPtr &msgp) {
uf_common::VelocityMeasurements const & msg = *msgp;
void got_dvl(const mil_msgs::VelocityMeasurementsConstPtr &msgp) {
mil_msgs::VelocityMeasurements const & msg = *msgp;

tf::StampedTransform transform;
try {
Expand All @@ -277,9 +277,9 @@ class NodeImpl {
Vec<3> local_dvl_pos; tf::vectorTFToEigen(transform.getOrigin(), local_dvl_pos);
Quaternion local_dvl_orientation; tf::quaternionTFToEigen(transform.getRotation(), local_dvl_orientation);

std::vector<uf_common::VelocityMeasurement> good;
std::vector<mil_msgs::VelocityMeasurement> good;
for(unsigned int i = 0; i < msg.velocity_measurements.size(); i++) {
uf_common::VelocityMeasurement const & vm = msg.velocity_measurements[i];
mil_msgs::VelocityMeasurement const & vm = msg.velocity_measurements[i];
if(!std::isnan(vm.velocity)) {
good.push_back(vm);
}
Expand All @@ -303,7 +303,7 @@ class NodeImpl {

Vec<Dynamic> res(good.size());
for(unsigned int i = 0; i < good.size(); i++) {
uf_common::VelocityMeasurement const & vm = good[i];
mil_msgs::VelocityMeasurement const & vm = good[i];
res(i) = (xyz2vec(vm.direction).dot(dvl_vel) + measurement_noise(i)) - vm.velocity;
}
return res;
Expand All @@ -314,8 +314,8 @@ class NodeImpl {
*state);
}

void got_depth(const uf_common::Float64StampedConstPtr &msgp) {
uf_common::Float64Stamped const & msg = *msgp;
void got_depth(const mil_msgs::DepthStampedConstPtr &msgp) {
mil_msgs::DepthStamped const & msg = *msgp;


tf::StampedTransform transform;
Expand All @@ -335,7 +335,7 @@ class NodeImpl {
[&](State const &state, Vec<1> const &measurement_noise) {
SqMat<3> m = enu_from_ecef_mat(state.getPosECEF());
double estimated = -(m * state.getRelPosECEF(local_depth_pos))(2) + measurement_noise(0);
return scalar_matrix(estimated - msg.data);
return scalar_matrix(estimated - msg.depth);
},
GaussianDistribution<Vec<1> >(
Vec<1>::Zero(),
Expand All @@ -354,10 +354,10 @@ class NodeImpl {
ros::Subscriber imu_sub;
message_filters::Subscriber<sensor_msgs::MagneticField> mag_sub;
tf::MessageFilter<sensor_msgs::MagneticField> mag_filter;
message_filters::Subscriber<uf_common::VelocityMeasurements> dvl_sub;
tf::MessageFilter<uf_common::VelocityMeasurements> dvl_filter;
message_filters::Subscriber<uf_common::Float64Stamped> depth_sub;
tf::MessageFilter<uf_common::Float64Stamped> depth_filter;
message_filters::Subscriber<mil_msgs::VelocityMeasurements> dvl_sub;
tf::MessageFilter<mil_msgs::VelocityMeasurements> dvl_filter;
message_filters::Subscriber<mil_msgs::DepthStamped> depth_sub;
tf::MessageFilter<mil_msgs::DepthStamped> depth_filter;
ros::Publisher odom_pub;
ros::Publisher absodom_pub;
ros::Publisher info_pub;
Expand Down

0 comments on commit 299eb06

Please sign in to comment.