Skip to content

Commit

Permalink
update namespace name
Browse files Browse the repository at this point in the history
  • Loading branch information
vkopli committed Mar 4, 2020
1 parent 865352e commit 1c6144f
Show file tree
Hide file tree
Showing 20 changed files with 64 additions and 64 deletions.
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
set(isam2_node "isam2_vio_zedpose")

cmake_minimum_required(VERSION 2.8.12)
project(legged_vio)
project(gtsam_vio)

add_compile_options(-std=c++11)

Expand Down Expand Up @@ -134,12 +134,12 @@ target_link_libraries(image_processor_nodelet
${catkin_LIBRARIES}
)

# custom ISAM2 nodes (TODO: move new launch params from image_processor_nodelet to new nodelet)
# custom ISAM2 nodes

# ISAM2 combined vision and zed pose node
add_executable(isam2 src/${isam2_node}.cpp)
target_link_libraries(isam2 ${catkin_LIBRARIES} gtsam)
add_dependencies(isam2 legged_vio_generate_messages_cpp)
add_dependencies(isam2 gtsam_vio_generate_messages_cpp)

#############
## Install ##
Expand Down
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ To change frame and camera topic specifications:
## Instructions to Run

Run launch file:
- roslaunch legged_vio isam2_minitaur_zed.launch
- roslaunch gtsam_vio isam2_minitaur_zed.launch

For the launch file to work, the following topics should be publishing messages:
- /zed/zed_node/left/image_rect_color/compressed
Expand All @@ -38,4 +38,4 @@ The following topics may be helpful:
## Instructions to Visualize

To visualize the estimated camera pose and 3D locations of features in the world frame, run the following command:
- rviz rviz -d ~/catkin_ws/src/legged_vio/rviz/rviz_tf_features_config.rviz
- rviz rviz -d ~/catkin_ws/src/gtsam_vio/rviz/rviz_tf_features_config.rviz
10 changes: 5 additions & 5 deletions include/legged_vio/cam_state.h → include/gtsam_vio/cam_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,16 @@
* All rights reserved.
*/

#ifndef LEGGED_VIO_CAM_STATE_H
#define LEGGED_VIO_CAM_STATE_H
#ifndef GTSAM_VIO_CAM_STATE_H
#define GTSAM_VIO_CAM_STATE_H

#include <map>
#include <vector>
#include <Eigen/Dense>

#include "imu_state.h"

namespace legged_vio {
namespace gtsam_vio {
/*
* @brief CAMState Stored camera state in order to
* form measurement model.
Expand Down Expand Up @@ -62,6 +62,6 @@ struct CAMState {
typedef std::map<StateIDType, CAMState, std::less<int>,
Eigen::aligned_allocator<
std::pair<const StateIDType, CAMState> > > CamStateServer;
} // namespace legged_vio
} // namespace gtsam_vio

#endif // LEGGED_VIO_CAM_STATE_H
#endif // GTSAM_VIO_CAM_STATE_H
10 changes: 5 additions & 5 deletions include/legged_vio/feature.hpp → include/gtsam_vio/feature.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
* All rights reserved.
*/

#ifndef LEGGED_VIO_FEATURE_H
#define LEGGED_VIO_FEATURE_H
#ifndef GTSAM_VIO_FEATURE_H
#define GTSAM_VIO_FEATURE_H

#include <iostream>
#include <map>
Expand All @@ -20,7 +20,7 @@
#include "imu_state.h"
#include "cam_state.h"

namespace legged_vio {
namespace gtsam_vio {

/*
* @brief Feature Salient part of an image. Please refer
Expand Down Expand Up @@ -435,6 +435,6 @@ bool Feature::initializePosition(

return is_valid_solution;
}
} // namespace legged_vio
} // namespace gtsam_vio

#endif // LEGGED_VIO_FEATURE_H
#endif // GTSAM_VIO_FEATURE_H
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
* All rights reserved.
*/

#ifndef LEGGED_VIO_IMAGE_PROCESSOR_H
#define LEGGED_VIO_IMAGE_PROCESSOR_H
#ifndef GTSAM_VIO_IMAGE_PROCESSOR_H
#define GTSAM_VIO_IMAGE_PROCESSOR_H

#include <vector>
#include <map>
Expand All @@ -22,7 +22,7 @@
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>

namespace legged_vio {
namespace gtsam_vio {

/*
* @brief ImageProcessor Detects and tracks features
Expand Down Expand Up @@ -393,6 +393,6 @@ class ImageProcessor {
typedef ImageProcessor::Ptr ImageProcessorPtr;
typedef ImageProcessor::ConstPtr ImageProcessorConstPtr;

} // end namespace legged_vio
} // end namespace gtsam_vio

#endif
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@

#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <legged_vio/image_processor.h>
#include <gtsam_vio/image_processor.h>

namespace legged_vio {
namespace gtsam_vio {
class ImageProcessorNodelet : public nodelet::Nodelet {
public:
ImageProcessorNodelet() { return; }
Expand All @@ -22,7 +22,7 @@ class ImageProcessorNodelet : public nodelet::Nodelet {
virtual void onInit();
ImageProcessorPtr img_processor_ptr;
};
} // end namespace legged_vio
} // end namespace gtsam_vio

#endif

Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@
* All rights reserved.
*/

#ifndef LEGGED_VIO_MATH_UTILS_HPP
#define LEGGED_VIO_MATH_UTILS_HPP
#ifndef GTSAM_VIO_MATH_UTILS_HPP
#define GTSAM_VIO_MATH_UTILS_HPP

#include <cmath>
#include <Eigen/Dense>

namespace legged {
namespace gtsam_vio {

/*
* @brief Create a skew-symmetric matrix from a 3-element vector.
Expand Down Expand Up @@ -158,6 +158,6 @@ inline Eigen::Vector4d rotationToQuaternion(
return q;
}

} // end namespace legged_vio
} // end namespace gtsam_vio

#endif // LEGGED_VIO_MATH_UTILS_HPP
#endif // GTSAM_VIO_MATH_UTILS_HPP
8 changes: 4 additions & 4 deletions include/legged_vio/utils.h → include/gtsam_vio/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,17 @@
* All rights reserved.
*/

#ifndef LEGGED_VIO_UTILS_H
#define LEGGED_VIO_UTILS_H
#ifndef GTSAM_VIO_UTILS_H
#define GTSAM_VIO_UTILS_H

#include <ros/ros.h>
#include <string>
#include <opencv2/core/core.hpp>
#include <Eigen/Geometry>

namespace legged_vio {
namespace gtsam_vio {
/*
* @brief utilities for legged_vio
* @brief utilities for gtsam_vio
*/
namespace utils {
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
Expand Down
6 changes: 3 additions & 3 deletions launch/isam2_minitaur_zed.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<!-- ImageProcessorNodelet/ISAM2 Variables -->
<arg name="robot" default="minitaur"/>
<arg name="calibration_file"
default="$(find legged_vio)/config/zed_imu_camera_altered.yaml"/>
default="$(find gtsam_vio)/config/zed_imu_camera_altered.yaml"/>

<!-- ISAM2 Variables -->
<arg name="images_compressed" default="true"/>
Expand All @@ -26,7 +26,7 @@
<!-- Image Processor Nodelet -->
<!-- (NOTE: to print output, include output="screen" command) -->
<node pkg="nodelet" type="nodelet" name="image_processor"
args="standalone legged_vio/ImageProcessorNodelet"> <!--output="screen"-->
args="standalone gtsam_vio/ImageProcessorNodelet"> <!--output="screen"-->

<rosparam command="load" file="$(arg calibration_file)"/>
<param name="grid_row" value="3"/>
Expand Down Expand Up @@ -61,7 +61,7 @@

<!-- ISAM2 Node -->
<!-- (NOTE: to print output, include output="screen" command) -->
<node pkg="legged_vio" name="isam2" type="isam2"
<node pkg="gtsam_vio" name="isam2" type="isam2"
required="true" output="screen"/>

<!-- Publish static transform between world and odom to visualized odom message from camera -->
Expand Down
4 changes: 2 additions & 2 deletions nodelets.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<library path="lib/libimage_processor_nodelet">
<class name="legged_vio/ImageProcessorNodelet"
type="legged_vio::ImageProcessorNodelet"
<class name="gtsam_vio/ImageProcessorNodelet"
type="gtsam_vio::ImageProcessorNodelet"
base_class_type="nodelet::Nodelet">
<description>
Detect and track features in image sequence.
Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<package format="2">

<name>legged_vio</name>
<name>gtsam_vio</name>
<version>0.0.1</version>
<description>Visual-Inertial State Estimation for legged robots with GTSAM</description>
<description>Visual-Inertial State Estimation using GTSAM</description>

<maintainer email="[email protected]">Vasileios Vasilopoulos</maintainer>

Expand Down
12 changes: 6 additions & 6 deletions src/image_processor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,16 +13,16 @@
#include <sensor_msgs/image_encodings.h>
#include <random_numbers/random_numbers.h>

#include <legged_vio/CameraMeasurement.h>
#include <legged_vio/TrackingInfo.h>
#include <legged_vio/image_processor.h>
#include <legged_vio/utils.h>
#include <gtsam_vio/CameraMeasurement.h>
#include <gtsam_vio/TrackingInfo.h>
#include <gtsam_vio/image_processor.h>
#include <gtsam_vio/utils.h>

using namespace std;
using namespace cv;
using namespace Eigen;

namespace legged_vio {
namespace gtsam_vio {
ImageProcessor::ImageProcessor(ros::NodeHandle& n) :
nh(n),
is_first_img(true),
Expand Down Expand Up @@ -1486,4 +1486,4 @@ void ImageProcessor::featureLifetimeStatistics() {
return;
}

} // end namespace legged_vio
} // end namespace gtsam_vio
8 changes: 4 additions & 4 deletions src/image_processor_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
* All rights reserved.
*/

#include <legged_vio/image_processor_nodelet.h>
#include <gtsam_vio/image_processor_nodelet.h>

namespace legged_vio {
namespace gtsam_vio {
void ImageProcessorNodelet::onInit() {
img_processor_ptr.reset(new ImageProcessor(getPrivateNodeHandle()));
if (!img_processor_ptr->initialize()) {
Expand All @@ -17,7 +17,7 @@ void ImageProcessorNodelet::onInit() {
return;
}

PLUGINLIB_EXPORT_CLASS(legged_vio::ImageProcessorNodelet, nodelet::Nodelet);
PLUGINLIB_EXPORT_CLASS(gtsam_vio::ImageProcessorNodelet, nodelet::Nodelet);

} // end namespace legged_vio
} // end namespace gtsam_vio

4 changes: 2 additions & 2 deletions src/isam2_imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include <sensor_msgs/Imu.h>
#include <tf/transform_broadcaster.h>
#include <tf_conversions/tf_eigen.h>
#include <legged_vio/CameraMeasurement.h>
#include <gtsam_vio/CameraMeasurement.h>

#include <sensor_msgs/PointCloud2.h>
#include <pcl_ros/point_cloud.h>
Expand Down Expand Up @@ -61,7 +61,7 @@

using namespace std;
using namespace message_filters;
using namespace legged_vio;
using namespace gtsam_vio;
using namespace sensor_msgs;
using namespace gtsam;

Expand Down
4 changes: 2 additions & 2 deletions src/isam2_vio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

#include <legged_vio/CameraMeasurement.h>
#include <gtsam_vio/CameraMeasurement.h>
#include <nav_msgs/Odometry.h>
#include <tf/transform_broadcaster.h>
#include <tf_conversions/tf_eigen.h>
Expand Down Expand Up @@ -53,7 +53,7 @@
#include <map>
#include <opencv2/opencv.hpp>

using namespace legged_vio;
using namespace gtsam_vio;
using namespace gtsam;

// PARAMETERS TO SPECIFY FOR OTHER NODES
Expand Down
4 changes: 2 additions & 2 deletions src/isam2_vio_imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include <sensor_msgs/Imu.h>
#include <tf/transform_broadcaster.h>
#include <tf_conversions/tf_eigen.h>
#include <legged_vio/CameraMeasurement.h>
#include <gtsam_vio/CameraMeasurement.h>

#include <sensor_msgs/PointCloud2.h>
#include <pcl_ros/point_cloud.h>
Expand Down Expand Up @@ -59,7 +59,7 @@

using namespace std;
using namespace message_filters;
using namespace legged_vio;
using namespace gtsam_vio;
using namespace sensor_msgs;
using namespace gtsam;

Expand Down
4 changes: 2 additions & 2 deletions src/isam2_vio_zedpose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

#include <legged_vio/CameraMeasurement.h>
#include <gtsam_vio/CameraMeasurement.h>
#include <nav_msgs/Odometry.h>
#include <tf/transform_broadcaster.h>
#include <tf_conversions/tf_eigen.h>
Expand Down Expand Up @@ -56,7 +56,7 @@
#include <memory>
#include <opencv2/opencv.hpp>

using namespace legged_vio;
using namespace gtsam_vio;
using namespace gtsam;

// PARAMETERS TO SPECIFY FOR OTHER NODES
Expand Down
6 changes: 3 additions & 3 deletions src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
* All rights reserved.
*/

#include <legged_vio/utils.h>
#include <gtsam_vio/utils.h>
#include <vector>

namespace legged_vio {
namespace gtsam_vio {
namespace utils {

Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
Expand Down Expand Up @@ -89,4 +89,4 @@ cv::Mat getKalibrStyleTransform(const ros::NodeHandle &nh,
}

} // namespace utils
} // namespace legged_vio
} // namespace gtsam_vio
6 changes: 3 additions & 3 deletions test/feature_initialization_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,13 @@
#include <gtest/gtest.h>
#include <random_numbers/random_numbers.h>

#include <legged_vio/cam_state.h>
#include <legged_vio/feature.hpp>
#include <gtsam_vio/cam_state.h>
#include <gtsam_vio/feature.hpp>


using namespace std;
using namespace Eigen;
using namespace legged_vio;
using namespace gtsam_vio;

// Static member variables in CAMState class
Isometry3d CAMState::T_cam0_cam1 = Isometry3d::Identity();
Expand Down
Loading

0 comments on commit 1c6144f

Please sign in to comment.