Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

make: *** [all] Error 2 #979

Open
wants to merge 12 commits into
base: master
Choose a base branch
from
13 changes: 2 additions & 11 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(OpenCV 2.4.3 REQUIRED)
find_package(OpenCV 3 REQUIRED)
find_package(Eigen3 3.1.0 REQUIRED)
find_package(Pangolin REQUIRED)

Expand Down Expand Up @@ -77,19 +77,14 @@ set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D)

add_executable(rgbd_tum
Examples/RGB-D/rgbd_tum.cc)
target_link_libraries(rgbd_tum ${PROJECT_NAME})
target_link_libraries(rgbd_tum ${PROJECT_NAME} ${OpenCV_LIBS} opencv_core opencv_videoio opencv_highgui opencv_imgcodecs )

set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Stereo)

add_executable(stereo_kitti
Examples/Stereo/stereo_kitti.cc)
target_link_libraries(stereo_kitti ${PROJECT_NAME})

add_executable(stereo_euroc
Examples/Stereo/stereo_euroc.cc)
target_link_libraries(stereo_euroc ${PROJECT_NAME})


set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Monocular)

add_executable(mono_tum
Expand All @@ -100,7 +95,3 @@ add_executable(mono_kitti
Examples/Monocular/mono_kitti.cc)
target_link_libraries(mono_kitti ${PROJECT_NAME})

add_executable(mono_euroc
Examples/Monocular/mono_euroc.cc)
target_link_libraries(mono_euroc ${PROJECT_NAME})

2 changes: 1 addition & 1 deletion Examples/ROS/ORB_SLAM2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)

find_package(OpenCV 2.4.3 REQUIRED)
find_package(OpenCV 3 REQUIRED)
find_package(Eigen3 3.1.0 REQUIRED)
find_package(Pangolin REQUIRED)

Expand Down
306 changes: 306 additions & 0 deletions Examples/ROS/ORB_SLAM2/DenseInput.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,306 @@
// Generated by gencpp from file svo_msgs/DenseInput.msg
// DO NOT EDIT!


#ifndef SVO_MSGS_MESSAGE_DENSEINPUT_H
#define SVO_MSGS_MESSAGE_DENSEINPUT_H


#include <string>
#include <vector>
#include <map>

#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>

#include <std_msgs/Header.h>
#include <geometry_msgs/Pose.h>
#include <sensor_msgs/Image.h>

namespace svo_msgs
{
template <class ContainerAllocator>
struct DenseInput_
{
typedef DenseInput_<ContainerAllocator> Type;

DenseInput_()
: header()
, frame_id(0)
, pose()
, image()
, min_depth(0.0)
, max_depth(0.0) {
}
DenseInput_(const ContainerAllocator& _alloc)
: header(_alloc)
, frame_id(0)
, pose(_alloc)
, image(_alloc)
, min_depth(0.0)
, max_depth(0.0) {
(void)_alloc;
}



typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
_header_type header;

typedef uint32_t _frame_id_type;
_frame_id_type frame_id;

typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type;
_pose_type pose;

typedef ::sensor_msgs::Image_<ContainerAllocator> _image_type;
_image_type image;

typedef float _min_depth_type;
_min_depth_type min_depth;

typedef float _max_depth_type;
_max_depth_type max_depth;




typedef boost::shared_ptr< ::svo_msgs::DenseInput_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::svo_msgs::DenseInput_<ContainerAllocator> const> ConstPtr;

}; // struct DenseInput_

typedef ::svo_msgs::DenseInput_<std::allocator<void> > DenseInput;

typedef boost::shared_ptr< ::svo_msgs::DenseInput > DenseInputPtr;
typedef boost::shared_ptr< ::svo_msgs::DenseInput const> DenseInputConstPtr;

// constants requiring out of line definition



template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const ::svo_msgs::DenseInput_<ContainerAllocator> & v)
{
ros::message_operations::Printer< ::svo_msgs::DenseInput_<ContainerAllocator> >::stream(s, "", v);
return s;
}

} // namespace svo_msgs

namespace ros
{
namespace message_traits
{



// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'sensor_msgs': ['/opt/ros/kinetic/share/sensor_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'svo_msgs': ['/home/ayush/catkin_ws/src/svo_msgs/msg']}

// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']




template <class ContainerAllocator>
struct IsFixedSize< ::svo_msgs::DenseInput_<ContainerAllocator> >
: FalseType
{ };

template <class ContainerAllocator>
struct IsFixedSize< ::svo_msgs::DenseInput_<ContainerAllocator> const>
: FalseType
{ };

template <class ContainerAllocator>
struct IsMessage< ::svo_msgs::DenseInput_<ContainerAllocator> >
: TrueType
{ };

template <class ContainerAllocator>
struct IsMessage< ::svo_msgs::DenseInput_<ContainerAllocator> const>
: TrueType
{ };

template <class ContainerAllocator>
struct HasHeader< ::svo_msgs::DenseInput_<ContainerAllocator> >
: TrueType
{ };

template <class ContainerAllocator>
struct HasHeader< ::svo_msgs::DenseInput_<ContainerAllocator> const>
: TrueType
{ };


template<class ContainerAllocator>
struct MD5Sum< ::svo_msgs::DenseInput_<ContainerAllocator> >
{
static const char* value()
{
return "cea677f47dcf08581cc9f5efece2f7e7";
}

static const char* value(const ::svo_msgs::DenseInput_<ContainerAllocator>&) { return value(); }
static const uint64_t static_value1 = 0xcea677f47dcf0858ULL;
static const uint64_t static_value2 = 0x1cc9f5efece2f7e7ULL;
};

template<class ContainerAllocator>
struct DataType< ::svo_msgs::DenseInput_<ContainerAllocator> >
{
static const char* value()
{
return "svo_msgs/DenseInput";
}

static const char* value(const ::svo_msgs::DenseInput_<ContainerAllocator>&) { return value(); }
};

template<class ContainerAllocator>
struct Definition< ::svo_msgs::DenseInput_<ContainerAllocator> >
{
static const char* value()
{
return "Header header\n\
uint32 frame_id\n\
geometry_msgs/Pose pose\n\
sensor_msgs/Image image\n\
float32 min_depth\n\
float32 max_depth\n\
================================================================================\n\
MSG: std_msgs/Header\n\
# Standard metadata for higher-level stamped data types.\n\
# This is generally used to communicate timestamped data \n\
# in a particular coordinate frame.\n\
# \n\
# sequence ID: consecutively increasing ID \n\
uint32 seq\n\
#Two-integer timestamp that is expressed as:\n\
# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
# time-handling sugar is provided by the client library\n\
time stamp\n\
#Frame this data is associated with\n\
# 0: no frame\n\
# 1: global frame\n\
string frame_id\n\
\n\
================================================================================\n\
MSG: geometry_msgs/Pose\n\
# A representation of pose in free space, composed of position and orientation. \n\
Point position\n\
Quaternion orientation\n\
\n\
================================================================================\n\
MSG: geometry_msgs/Point\n\
# This contains the position of a point in free space\n\
float64 x\n\
float64 y\n\
float64 z\n\
\n\
================================================================================\n\
MSG: geometry_msgs/Quaternion\n\
# This represents an orientation in free space in quaternion form.\n\
\n\
float64 x\n\
float64 y\n\
float64 z\n\
float64 w\n\
\n\
================================================================================\n\
MSG: sensor_msgs/Image\n\
# This message contains an uncompressed image\n\
# (0, 0) is at top-left corner of image\n\
#\n\
\n\
Header header # Header timestamp should be acquisition time of image\n\
# Header frame_id should be optical frame of camera\n\
# origin of frame should be optical center of cameara\n\
# +x should point to the right in the image\n\
# +y should point down in the image\n\
# +z should point into to plane of the image\n\
# If the frame_id here and the frame_id of the CameraInfo\n\
# message associated with the image conflict\n\
# the behavior is undefined\n\
\n\
uint32 height # image height, that is, number of rows\n\
uint32 width # image width, that is, number of columns\n\
\n\
# The legal values for encoding are in file src/image_encodings.cpp\n\
# If you want to standardize a new string format, join\n\
# [email protected] and send an email proposing a new encoding.\n\
\n\
string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
# taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
\n\
uint8 is_bigendian # is this data bigendian?\n\
uint32 step # Full row length in bytes\n\
uint8[] data # actual matrix data, size is (step * rows)\n\
";
}

static const char* value(const ::svo_msgs::DenseInput_<ContainerAllocator>&) { return value(); }
};

} // namespace message_traits
} // namespace ros

namespace ros
{
namespace serialization
{

template<class ContainerAllocator> struct Serializer< ::svo_msgs::DenseInput_<ContainerAllocator> >
{
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
{
stream.next(m.header);
stream.next(m.frame_id);
stream.next(m.pose);
stream.next(m.image);
stream.next(m.min_depth);
stream.next(m.max_depth);
}

ROS_DECLARE_ALLINONE_SERIALIZER;
}; // struct DenseInput_

} // namespace serialization
} // namespace ros

namespace ros
{
namespace message_operations
{

template<class ContainerAllocator>
struct Printer< ::svo_msgs::DenseInput_<ContainerAllocator> >
{
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::svo_msgs::DenseInput_<ContainerAllocator>& v)
{
s << indent << "header: ";
s << std::endl;
Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
s << indent << "frame_id: ";
Printer<uint32_t>::stream(s, indent + " ", v.frame_id);
s << indent << "pose: ";
s << std::endl;
Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.pose);
s << indent << "image: ";
s << std::endl;
Printer< ::sensor_msgs::Image_<ContainerAllocator> >::stream(s, indent + " ", v.image);
s << indent << "min_depth: ";
Printer<float>::stream(s, indent + " ", v.min_depth);
s << indent << "max_depth: ";
Printer<float>::stream(s, indent + " ", v.max_depth);
}
};

} // namespace message_operations
} // namespace ros

#endif // SVO_MSGS_MESSAGE_DENSEINPUT_H
Loading