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

Keep compatibility with earlier Gazebo version #45

Merged
merged 1 commit into from
Mar 3, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 0 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,11 +1,5 @@
# Intel RealSense Gazebo ROS plugin and model

## _**Important note**_

**This branch only supports ROS Melodic with Gazebo 9.**

**To use this plugin with ROS Kinetic and Gazebo 7 you should use the [`kinetic-devel` branch](https://github.com/SyrianSpock/realsense_gazebo_plugin/tree/kinetic-devel).**

## Quickstart

Build the plugin
Expand Down
12 changes: 12 additions & 0 deletions src/RealSensePlugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,11 @@ void RealSensePlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)

// Setup Transport Node
this->transportNode = transport::NodePtr(new transport::Node());
#if GAZEBO_MAJOR_VERSION >= 9
this->transportNode->Init(this->world->Name());
#else
this->transportNode->Init(this->world->GetName());
#endif

// Setup Publishers
std::string rsTopicRoot =
Expand Down Expand Up @@ -166,7 +170,11 @@ void RealSensePlugin::OnNewFrame(const rendering::CameraPtr cam,
msgs::ImageStamped msg;

// Set Simulation Time
#if GAZEBO_MAJOR_VERSION >= 9
msgs::Set(msg.mutable_time(), this->world->SimTime());
#else
msgs::Set(msg.mutable_time(), this->world->GetSimTime());
#endif

// Set Image Dimensions
msg.mutable_image()->set_width(cam->ImageWidth());
Expand Down Expand Up @@ -215,7 +223,11 @@ void RealSensePlugin::OnNewDepthFrame()
}

// Pack realsense scaled depth map
#if GAZEBO_MAJOR_VERSION >= 9
msgs::Set(msg.mutable_time(), this->world->SimTime());
#else
msgs::Set(msg.mutable_time(), this->world->GetSimTime());
#endif
msg.mutable_image()->set_width(this->depthCam->ImageWidth());
msg.mutable_image()->set_height(this->depthCam->ImageHeight());
msg.mutable_image()->set_pixel_format(common::Image::L_INT16);
Expand Down
8 changes: 8 additions & 0 deletions src/gazebo_ros_realsense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,11 @@ void GazeboRosRealsense::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
void GazeboRosRealsense::OnNewFrame(const rendering::CameraPtr cam,
const transport::PublisherPtr pub)
{
#if GAZEBO_MAJOR_VERSION >= 9
common::Time current_time = this->world->SimTime();
#else
common::Time current_time = this->world->GetSimTime();
#endif

// identify camera
std::string camera_id = extractCameraName(cam->Name());
Expand Down Expand Up @@ -96,7 +100,11 @@ void GazeboRosRealsense::OnNewFrame(const rendering::CameraPtr cam,
void GazeboRosRealsense::OnNewDepthFrame()
{
// get current time
#if GAZEBO_MAJOR_VERSION >= 9
common::Time current_time = this->world->SimTime();
#else
common::Time current_time = this->world->GetSimTime();
#endif

RealSensePlugin::OnNewDepthFrame();

Expand Down