Skip to content

Commit

Permalink
ros_noetic update
Browse files Browse the repository at this point in the history
  • Loading branch information
danielemorra98 committed Nov 29, 2021
1 parent 9a85997 commit e831d27
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
12 changes: 7 additions & 5 deletions rotors_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@ add_definitions(-std=c++11)
# We need Gazebo version >= 3.0.0 to generate iris.sdf file
# (gz sdf ... command needs to be available)
find_package(gazebo REQUIRED)
find_package(PythonInterp REQUIRED)


if(${gazebo_VERSION_MAJOR} GREATER 2)
message(STATUS "Building iris.sdf.")
Expand All @@ -26,7 +28,7 @@ if(${gazebo_VERSION_MAJOR} GREATER 2)
add_custom_command(OUTPUT ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
COMMAND rm -f ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
COMMAND python ${scripts_dir}/xacro.py -o ${rotors_description_dir}/urdf/iris_base.urdf ${rotors_description_dir}/urdf/iris_base.xacro enable_mavlink_interface:=${enable_mavlink_interface} enable_ground_truth:=${enable_ground_truth} enable_wind:=${enable_wind} enable_logging:=${enable_logging} rotors_description_dir:=${rotors_description_dir}
COMMAND ${PYTHON_EXECUTABLE} ${scripts_dir}/xacro.py -o ${rotors_description_dir}/urdf/iris_base.urdf ${rotors_description_dir}/urdf/iris_base.xacro enable_mavlink_interface:=${enable_mavlink_interface} enable_ground_truth:=${enable_ground_truth} enable_wind:=${enable_wind} enable_logging:=${enable_logging} rotors_description_dir:=${rotors_description_dir}
COMMAND gz sdf -p ${rotors_description_dir}/urdf/iris_base.urdf >> ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
COMMAND rm -f ${rotors_description_dir}/urdf/iris_base.urdf
DEPENDS ${rotors_description_dir}/urdf/iris.xacro
Expand Down Expand Up @@ -55,20 +57,20 @@ find_package(catkin REQUIRED COMPONENTS
)

find_package(
Eigen REQUIRED
Eigen3 REQUIRED
)

catkin_package(
INCLUDE_DIRS include ${Eigen_INCLUDE_DIRS}
INCLUDE_DIRS include ${Eigen3_INCLUDE_DIRS}
LIBRARIES spline_trajectory_generator
CATKIN_DEPENDS geometry_msgs mav_msgs nav_msgs roscpp sensor_msgs gazebo_msgs
DEPENDS Eigen
DEPENDS Eigen3
)

include_directories(
include
${catkin_INCLUDE_DIRS}
${Eigen_INCLUDE_DIRS}
${Eigen3_INCLUDE_DIRS}
)

add_library(spline_trajectory_generator
Expand Down
2 changes: 1 addition & 1 deletion rotors_gazebo/launch/spawn_mav_crazyflie.launch
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

<!-- send the robot XML to param server -->
<param name="robot_description" command="
$(find xacro)/xacro --inorder '$(arg model)'
$(find xacro)/xacro '$(arg model)'
enable_logging:=$(arg enable_logging)
enable_mellinger_controller:=$(arg enable_mellinger_controller)
enable_internal_model_controller:=$(arg enable_internal_model_controller)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
#include <iostream>

#include <boost/filesystem.hpp>
#include <cv.h>
#include <highgui.h>
#include <opencv2/opencv.hpp>

#include "rotors_gazebo_plugins/common.h"
Expand Down Expand Up @@ -140,7 +138,7 @@ void GeotaggedImagesPlugin::OnNewFrame(const unsigned char * image)
Mat frame = Mat(height_, width_, CV_8UC3);
Mat frameBGR = Mat(height_, width_, CV_8UC3);
frame.data = (uchar*)image; //frame has not the right color format yet -> convert
cvtColor(frame, frameBGR, CV_RGB2BGR);
cvtColor(frame, frameBGR, cv::COLOR_RGB2BGR);

char file_name[256];
snprintf(file_name, sizeof(file_name), "%s/DSC%05i.jpg", storageDir_.c_str(), imageCounter_);
Expand Down
2 changes: 1 addition & 1 deletion rotors_gazebo_plugins/src/gazebo_odometry_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void GazeboOdometryPlugin::Load(physics::ModelPtr _model,
if (_sdf->HasElement("covarianceImage")) {
std::string image_name =
_sdf->GetElement("covarianceImage")->Get<std::string>();
covariance_image_ = cv::imread(image_name, CV_LOAD_IMAGE_GRAYSCALE);
covariance_image_ = cv::imread(image_name, cv::IMREAD_GRAYSCALE);
if (covariance_image_.data == NULL)
gzerr << "loading covariance image " << image_name << " failed"
<< std::endl;
Expand Down

0 comments on commit e831d27

Please sign in to comment.