Skip to content

Commit

Permalink
[ros2] Port projector to ROS2 (#956)
Browse files Browse the repository at this point in the history
* [ros2] Port projector to ROS2

* fix small typo
  • Loading branch information
shiveshkhaitan authored and chapulina committed Jul 27, 2019
1 parent 22d782e commit 5b71809
Show file tree
Hide file tree
Showing 9 changed files with 401 additions and 303 deletions.

This file was deleted.

176 changes: 0 additions & 176 deletions .ros1_unported/gazebo_plugins/src/gazebo_ros_projector.cpp

This file was deleted.

13 changes: 13 additions & 0 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -201,6 +201,18 @@ target_link_libraries(gazebo_ros_elevator
)
ament_export_libraries(gazebo_ros_elevator)

# gazebo_ros_projector
add_library(gazebo_ros_projector SHARED
src/gazebo_ros_projector.cpp
)
ament_target_dependencies(gazebo_ros_projector
"gazebo_ros"
"gazebo_dev"
"rclcpp"
"std_msgs"
)
ament_export_libraries(gazebo_ros_projector)

ament_export_include_directories(include)
ament_export_dependencies(rclcpp)
ament_export_dependencies(gazebo_dev)
Expand All @@ -225,6 +237,7 @@ install(TARGETS
gazebo_ros_ft_sensor
gazebo_ros_imu_sensor
gazebo_ros_joint_state_publisher
gazebo_ros_projector
gazebo_ros_ray_sensor
gazebo_ros_p3d
gazebo_ros_template
Expand Down
63 changes: 63 additions & 0 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_projector.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
// Copyright 2019 Open Source Robotics Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_PROJECTOR_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_PROJECTOR_HPP_

#include <gazebo/common/Plugin.hh>

#include <memory>

namespace gazebo_plugins
{
class GazeboRosProjectorPrivate;

/// A projector plugin for gazebo.
/**
Example Usage:
\code{.xml}
<!-- Plugin to control the projector -->
<plugin name="projector" filename="libgazebo_ros_projector.so">
<ros>
<namespace>demo</namespace>
<!-- topic remapping -->
<argument>switch:=switch_demo</argument>
<projector_link>projector_link</projector_link>
<projector_name>my_projector</projector_name>
</ros>
\endcode
*/
class GazeboRosProjector : public gazebo::ModelPlugin
{
public:
/// Constructor
GazeboRosProjector();

/// Destructor
~GazeboRosProjector();

protected:
// Documentation inherited
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override;

private:
/// Private data pointer
std::unique_ptr<GazeboRosProjectorPrivate> impl_;
};
} // namespace gazebo_plugins

#endif // GAZEBO_PLUGINS__GAZEBO_ROS_PROJECTOR_HPP_
Loading

0 comments on commit 5b71809

Please sign in to comment.