Skip to content
Snippets Groups Projects
Commit d1eed341 authored by Mederic Fourmy's avatar Mederic Fourmy
Browse files

Merge branch '1-publisher-for-visual-odometry' into 'devel'

Resolve "Publisher for visual odometry"

Closes #1

See merge request !1
parents 627235af 64072ebd
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1Resolve "Publisher for visual odometry"
Pipeline #10747 passed
.vscode/
.cproject
.project
.settings/language.settings.xml
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 3.0.2)
project(wolf_ros_vision) project(wolf_ros_vision)
## Compile as C++14 ## Compile as C++14
...@@ -6,113 +6,32 @@ add_compile_options(-std=c++14) ...@@ -6,113 +6,32 @@ add_compile_options(-std=c++14)
# -fPIC and -rdynamic ensure unique singleton instance across shared libraries (for factories) see: https://stackoverflow.com/a/8626922 # -fPIC and -rdynamic ensure unique singleton instance across shared libraries (for factories) see: https://stackoverflow.com/a/8626922
SET(CMAKE_CXX_FLAGS "-fPIC -rdynamic") SET(CMAKE_CXX_FLAGS "-fPIC -rdynamic")
# SET(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/wolf_ros_wrapper/cmake_modules")
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS find_package(catkin REQUIRED COMPONENTS
roscpp roscpp
rospy
sensor_msgs sensor_msgs
std_msgs
tf
dynamic_reconfigure
wolf_ros_node wolf_ros_node
cv_bridge cv_bridge
image_transport image_transport
) )
## System dependencies are found with CMake's conventions ## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system) find_package(OpenCV REQUIRED)
# find_package(Ceres REQUIRED)
# find_package(Eigen3 REQUIRED)
find_package(wolfcore REQUIRED) find_package(wolfcore REQUIRED)
find_package(wolfvision REQUIRED) find_package(wolfvision REQUIRED)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
#generate_messages(
# DEPENDENCIES
#)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
#generate_dynamic_reconfigure_options(
# cfg/WolfROS.cfg
#)
################################### ###################################
## catkin specific configuration ## ## catkin specific configuration ##
################################### ###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package( catkin_package(
# INCLUDE_DIRS include CATKIN_DEPENDS rospy sensor_msgs
# LIBRARIES wolf_ros1
# CATKIN_DEPENDS roscpp sensor_msgs std_msgs
# DEPENDS system_lib
) )
########### ###########
...@@ -130,91 +49,26 @@ include_directories( ...@@ -130,91 +49,26 @@ include_directories(
${catkin_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS}
) )
# link_directories(/usr/local/lib/iri-algorithms)
## Declare a C++ library
add_library(subscriber_${PROJECT_NAME}
src/subscriber_camera.cpp)
#add_library(publisher_${PROJECT_NAME}
# src/publisher_camera.cpp)
## Add cmake target dependencies of the library ## Declare a C++ library
## as an example, code may need to be generated before libraries add_library(publisher_${PROJECT_NAME} src/publisher_vision.cpp)
## either from message generation or dynamic reconfigure add_library(subscriber_${PROJECT_NAME} src/subscriber_camera.cpp)
# add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg)
# add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg)
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg"
# set_target_properties(${PROJECT_NAME} PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
#add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg)
#add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg)
## Specify libraries to link a library or executable target against ## Specify libraries to link a library or executable target against
target_link_libraries(subscriber_${PROJECT_NAME} target_link_libraries(subscriber_${PROJECT_NAME}
${wolfcore_LIBRARIES} ${wolfcore_LIBRARIES}
${wolfvision_LIBRARIES} ${wolfvision_LIBRARIES}
${vision_utils_LIBRARY} ${catkin_LIBRARIES}
${catkin_LIBRARIES} ${sensor_msgs_LIBRARIES}
) )
#target_link_libraries(publisher_${PROJECT_NAME} target_link_libraries(publisher_${PROJECT_NAME}
# ${wolfcore_LIBRARIES} ${wolfcore_LIBRARIES}
# ${wolfvision_LIBRARIES} ${wolfvision_LIBRARIES}
# ${sensor_msgs_LIBRARIES} ${catkin_LIBRARIES}
# ) ${sensor_msgs_LIBRARIES}
)
#############
## Install ## # Declar a python script
############# catkin_install_python(PROGRAMS scripts/publisher_camera_info.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# all install targets should use catkin DESTINATION variables )
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_wolf_ros.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
//--------LICENSE_START--------
//
// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC.
// Authors: Joan Solà Ortega (jsola@iri.upc.edu)
// All rights reserved.
//
// This file is part of WOLF
// WOLF is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
//--------LICENSE_END--------
#ifndef PUBLISHER_VISION_DEBUG_H_
#define PUBLISHER_VISION_DEBUG_H_
/**************************
* WOLF includes *
**************************/
#include "core/common/wolf.h"
#include "vision/processor/processor_visual_odometry.h"
#include <core/utils/params_server.h>
#include "publisher.h"
/**************************
* ROS includes *
**************************/
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
namespace wolf
{
enum Color {BLUE = 0,
GREEN,
YELLOW,
MAGENTA,
CYAN,
GREY,
RED
};
class PublisherVisionDebug : public Publisher
{
public:
PublisherVisionDebug(const std::string& _unique_name,
const ParamsServer& _server,
const ProblemConstPtr _problem);
WOLF_PUBLISHER_CREATE(PublisherVisionDebug);
virtual ~PublisherVisionDebug(){};
void initialize(ros::NodeHandle &nh, const std::string& topic) override;
bool ready() override;
void publishDerived() override;
protected:
ProcessorVisualOdometryConstPtr processor_vision_;
CaptureBaseConstPtr last_capture_;
std::string topic_preprocessor_;
struct Feature {
double thickness_;
int size_pix_;
Color color_;
};
struct Tracks {
bool show_id_;
double size_id_;
double thickness_;
bool min_max_on_alive_tracks_;
Color color_;
int min_luminosity_;
int max_luminosity_;
Feature feature_last_;
Feature feature_kfs_;
};
struct Tracks_preprocess {
bool show_;
bool show_on_diff_topic_;
bool show_features_;
double thickness_;
Color color_;
};
struct Landmarks {
bool show_id_;
double size_id_;
int size_pix_;
Color color_;
};
Tracks tracks_;
Tracks_preprocess tracks_preprocess_;
Landmarks landmarks_;
image_transport::Publisher publisher_image_;
image_transport::Publisher publisher_image_preprocess_;
image_transport::ImageTransport img_transport_;
private:
cv::Scalar primaryColor(Color _color);
cv::Scalar colorTrackAndFeatures(int _nb_feature_in_track,
int _max_feature_in_tracks,
int _min_feature_in_tracks,
Color _color_of_features);
/*
Convert a string corresponding to a color to its corresponding Color enum value
*/
Color colorStringToEnum(const std::string _color);
/*
Search for the maximum and minimum of features in one track in the track matrix
*/
std::pair<int, int> minMaxAliveTrackLength(const TrackMatrix &_track_matrix, CaptureBaseConstPtr _cap_img) const;
/*
Return a unique RGB color vector depending on the lenght of the track given,
so the longer is the track the darker it is
*/
// std::vector<int> colorTrackAndFeatures(int _nb_feature_in_track, int _max_feature_in_tracks, int _min_feature_in_tracks, Color _color_of_features);
/*
Return a RGB color vector coresponding to the color asked
*/
// std::vector<int> primaryColor(Color _color_of_lmks);
/*
Change an image to show tracks and features within it
*/
void showTracks(cv::Mat _image, const TrackMatrix& _track_matrix, CaptureBaseConstPtr _cap_img);
/*
Return the transformation from world to camera
*/
Eigen::Isometry3d getTcw (const CaptureBaseConstPtr _capture) const;
/*
Transform Tcw into matrix for multiplication purpose
*/
Eigen::Matrix4d getTcwMatrix (const CaptureBaseConstPtr _capture) const;
/*
Return the projection matrix of a sensor (linked to a capture)
*/
Eigen::Matrix<double, 3, 4> getProjectionMatrix (const CaptureBaseConstPtr _capture) const;
/*
Return only the landmark associated to a feature in last keyframes
*/
LandmarkBaseConstPtr getAssociatedLandmark(const TrackMatrix& _track_matrix, const FeatureBaseConstPtr& _ftr);
/*
Return the projection of a landmark in the frame
*/
Eigen::Vector2d projectLandmarkHp (const Eigen::Matrix<double, 3, 4>& _trf_proj_mat, const LandmarkBaseConstPtr _lmk);
/*
Print one landmark into the capture
*/
void showLandmark (cv::Mat _image, const TrackMatrix& _track_matrix, const FeatureBasePtr& _ftr);
/*
Print all of the landmarks associated with the capture
*/
void showLandmarks (cv::Mat _image, const TrackMatrix& _track_matrix, const CaptureBaseConstPtr& _cap);
/*
Change an image to show tracks and features from the preprocess within it
*/
void showTracksPreprocess (cv::Mat _image, const CaptureImageConstPtr& _origin, const CaptureImageConstPtr& _last);
};
WOLF_REGISTER_PUBLISHER(PublisherVisionDebug)
}
#endif
...@@ -62,6 +62,7 @@ class SubscriberCamera : public Subscriber ...@@ -62,6 +62,7 @@ class SubscriberCamera : public Subscriber
SubscriberCamera(const std::string& _unique_name, SubscriberCamera(const std::string& _unique_name,
const ParamsServer& _server, const ParamsServer& _server,
const SensorBasePtr _sensor_ptr); const SensorBasePtr _sensor_ptr);
virtual ~SubscriberCamera(){};
WOLF_SUBSCRIBER_CREATE(SubscriberCamera); WOLF_SUBSCRIBER_CREATE(SubscriberCamera);
virtual void initialize(ros::NodeHandle& nh, const std::string& topic); virtual void initialize(ros::NodeHandle& nh, const std::string& topic);
......
...@@ -4,69 +4,33 @@ ...@@ -4,69 +4,33 @@
<version>0.0.0</version> <version>0.0.0</version>
<description>The wolf_ros package of WOLF project</description> <description>The wolf_ros package of WOLF project</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="jvallve@iri.upc.edu">jvallve</maintainer> <maintainer email="jvallve@iri.upc.edu">jvallve</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license> <license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/wolf_ros1</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend> <buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend> <build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend> <build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend> <build_depend>std_msgs</build_depend>
<build_depend>tf</build_depend> <build_depend>tf</build_depend>
<build_depend>wolf_ros_node</build_depend> <build_depend>wolf_ros_node</build_depend>
<build_export_depend>roscpp</build_export_depend> <build_export_depend>roscpp</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend> <build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>std_msgs</build_export_depend> <build_export_depend>std_msgs</build_export_depend>
<build_export_depend>tf</build_export_depend> <build_export_depend>tf</build_export_depend>
<exec_depend>roscpp</exec_depend> <exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>sensor_msgs</exec_depend> <exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend> <exec_depend>std_msgs</exec_depend>
<exec_depend>tf</exec_depend> <exec_depend>tf</exec_depend>
<exec_depend>wolf_ros_node</exec_depend> <exec_depend>wolf_ros_node</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export> <export>
<!-- Other tools can request additional information be placed here -->
</export> </export>
</package> </package>
#!/usr/bin/env python3
import sys
import copy
from pure_eval import CannotEval
import yaml
import numpy as np
import rospy
from sensor_msgs.msg import CameraInfo
from sensor_msgs.msg import Image
def kvec2mat(fx, fy, cx, cy):
return np.array([
fx, 0, cx,
0, fy, cy,
0, 0, 0
]).reshape((3,3))
def kmat2vec(K):
# fx, fy, cx, cy
return [K[0,0], K[1,1], K[0,2], K[1,2]]
class CameraInfoPublisher:
def __init__(self, topic_image_info_out, camera_yaml_path) -> None:
self.topic_image_info_out = topic_image_info_out
self.camera_yaml_path = camera_yaml_path
self.camera_info_msg = self.read_camera_info(camera_yaml_path)
self.publisher = rospy.Publisher(topic_image_info_out, CameraInfo, queue_size=10)
def read_camera_info(self, path: str) -> CameraInfo:
with open(path, 'r') as f:
d = yaml.safe_load(f)
# extract the important info and format them
return self.extract_info_standard_yaml(d)
def extract_info_standard_yaml(self, params: dict) -> CameraInfo:
# The yaml file should have the same structure as the ones used for wolf sensor camera
w = params['width']
h = params['height']
Kvec = params['camera_matrix']['data']
distortion_model = params['distortion_model']
D = params['distortion_coefficients']['data']
R = params['rectification_matrix']['data']
P = params['projection_matrix']['data']
msg_args = {
'width': w,
'height': h,
'K': Kvec,
'distortion_model': distortion_model,
'D': D,
'R': R,
'P': P,
}
return CameraInfo(**msg_args)
def publish_cam_info(self, image_msg: Image):
# take the header from image msg, replace the camera info header and then publish
self.camera_info_msg.header = image_msg.header
self.publisher.publish(self.camera_info_msg)
if __name__ == '__main__':
camera_yaml_path = rospy.get_param("camera_yaml_path")
topic_image_raw_in = rospy.get_param("topic_image_raw_in")
topic_image_info_out = rospy.get_param("topic_image_info_out")
rospy.init_node('camera_info_publisher', anonymous=True)
ci_publisher = CameraInfoPublisher(topic_image_info_out, camera_yaml_path)
sub = rospy.Subscriber(topic_image_raw_in, Image, ci_publisher.publish_cam_info)
print('Listening on ', sub.name)
rospy.spin()
\ No newline at end of file
This diff is collapsed.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment