Skip to content

Commit

Permalink
Changed data types to reflect the changes made for supporting c-98 in…
Browse files Browse the repository at this point in the history
… the inekf package.
  • Loading branch information
RossHartley committed Oct 16, 2018
1 parent 51cc13c commit 3c8e393
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 20 deletions.
13 changes: 4 additions & 9 deletions inekf_ros/include/Measurement.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@ class ImuMeasurement : public Measurement {

private:
Eigen::Matrix<double,6,1> data_;

//friend std::ostream& operator<<(std::ostream& os, const ImuMeasurement& m);
};


Expand All @@ -69,11 +67,10 @@ class LandmarkMeasurement : public Measurement {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
LandmarkMeasurement(const inekf_msgs::LandmarkArray::ConstPtr& msg, const tf::StampedTransform& transform);
inekf::vectorPairIntVector3d getData();
//friend std::ostream& operator<<(std::ostream& os, const Measurement& m);
inekf::vectorLandmarks getData();

private:
inekf::vectorPairIntVector3d data_;
inekf::vectorLandmarks data_;
};

class ContactMeasurement : public Measurement {
Expand All @@ -82,7 +79,6 @@ class ContactMeasurement : public Measurement {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
ContactMeasurement(const inekf_msgs::ContactArray::ConstPtr& msg);
std::vector<std::pair<int,bool>> getData();
//friend std::ostream& operator<<(std::ostream& os, const Measurement& m);

private:
std::vector<std::pair<int,bool>> data_;
Expand All @@ -94,11 +90,10 @@ class KinematicMeasurement : public Measurement {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
KinematicMeasurement(const inekf_msgs::KinematicsArray::ConstPtr& msg);
inekf::vectorTupleIntMatrix4dMatrix6d getData();
//friend std::ostream& operator<<(std::ostream& os, const Measurement& m);
inekf::vectorKinematics getData();

private:
inekf::vectorTupleIntMatrix4dMatrix6d data_;
inekf::vectorKinematics data_;
};


Expand Down
10 changes: 5 additions & 5 deletions inekf_ros/src/InEKF_ROS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -364,12 +364,12 @@ void InEKF_ROS::publishLandmarkMeasurementMarkers(shared_ptr<LandmarkMeasurement
base_point.y = position(1);
base_point.z = position(2);

vectorPairIntVector3d measured_landmarks = ptr->getData();
vectorLandmarks measured_landmarks = ptr->getData();
mapIntVector3d prior_landmarks = filter_.getPriorLandmarks();
map<int,int> estimated_landmarks = filter_.getEstimatedLandmarks();
for (auto it=measured_landmarks.begin(); it!=measured_landmarks.end(); ++it) {
// Search through prior landmarks
auto search_prior = prior_landmarks.find(it->first);
auto search_prior = prior_landmarks.find(it->id);
if (search_prior != prior_landmarks.end()) {
landmark_point.x = search_prior->second(0);
landmark_point.y = search_prior->second(1);
Expand All @@ -379,7 +379,7 @@ void InEKF_ROS::publishLandmarkMeasurementMarkers(shared_ptr<LandmarkMeasurement
continue;
}
// Search through estimated landmarks
auto search_estimated = estimated_landmarks.find(it->first);
auto search_estimated = estimated_landmarks.find(it->id);
if (search_estimated != estimated_landmarks.end()) {
landmark_point.x = X(0,search_estimated->second);
landmark_point.y = X(1,search_estimated->second);
Expand Down Expand Up @@ -421,11 +421,11 @@ void InEKF_ROS::publishKinematicMeasurementMarkers(shared_ptr<KinematicMeasureme
base_point.y = position(1);
base_point.z = position(2);

vectorTupleIntMatrix4dMatrix6d measured_kinematics = ptr->getData();
vectorKinematics measured_kinematics = ptr->getData();
map<int,int> estimated_contacts = filter_.getEstimatedContactPositions();
for (auto it=measured_kinematics.begin(); it!=measured_kinematics.end(); ++it) {
// Search through estimated contacts
auto search_estimated = estimated_contacts.find(get<0>(*it));
auto search_estimated = estimated_contacts.find(it->id);
if (search_estimated != estimated_contacts.end()) {
contact_point.x = X(0,search_estimated->second);
contact_point.y = X(1,search_estimated->second);
Expand Down
11 changes: 5 additions & 6 deletions inekf_ros/src/Measurement.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@ LandmarkMeasurement::LandmarkMeasurement(const inekf_msgs::LandmarkArray::ConstP
tf::Vector3 p_bl = transform*p_cl; // Transform measurement from camera frame to imu frame
Eigen::Vector3d position;
position << p_bl.getX(), p_bl.getY(), p_bl.getZ();
data_.push_back(pair<int,Eigen::Vector3d> (it->id, position));
data_.push_back(Landmark(it->id, position));
}
}
vectorPairIntVector3d LandmarkMeasurement::getData() { return data_; };
vectorLandmarks LandmarkMeasurement::getData() { return data_; };


// Construct Contact measurement
Expand Down Expand Up @@ -80,10 +80,10 @@ KinematicMeasurement::KinematicMeasurement(const inekf_msgs::KinematicsArray::Co
covariance(i,j) = it->pose.covariance[6*i+j]; // Assume row-major
}
}
data_.push_back(tuple<int,Eigen::Matrix4d,Eigen::Matrix<double,6,6>> (it->id, pose, covariance));
data_.push_back(Kinematics(it->id, pose, covariance));
}
}
vectorTupleIntMatrix4dMatrix6d KinematicMeasurement::getData() { return data_; };
vectorKinematics KinematicMeasurement::getData() { return data_; };

// Print measurement
ostream& operator<<(ostream& os, const Measurement& m) {
Expand All @@ -96,6 +96,5 @@ ostream& operator<<(ostream& os, const Measurement& m) {
type_str = "Unknown";
}
os << "Measurement type: " << type_str << endl;
//os << "Measurement time: " << m.t_ << endl;
//os << "Measurement data: \n" << m.data_ << endl;
return os;
}

0 comments on commit 3c8e393

Please sign in to comment.