Program Listing for File gazebo_ros_camera.hpp

Return to documentation for file (/tmp/ws/src/gazebo_ros_pkgs/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.hpp)

// Copyright 2012 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_CAMERA_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_CAMERA_HPP_

#include <gazebo/plugins/CameraPlugin.hh>
#include <gazebo/plugins/DepthCameraPlugin.hh>
#include <gazebo_plugins/multi_camera_plugin.hpp>
#include <gazebo_ros/node.hpp>

#include <rclcpp/node_interfaces/node_parameters_interface.hpp>
#include <std_msgs/msg/empty.hpp>

#include <memory>
#include <string>
#include <vector>

namespace gazebo_plugins
{
class GazeboRosCameraPrivate;


class GazeboRosCamera
  : public gazebo::CameraPlugin, gazebo::DepthCameraPlugin, MultiCameraPlugin
{
public:
  GazeboRosCamera();

  ~GazeboRosCamera();

protected:
  // Documentation inherited
  void Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) override;

  /*
   * \param[in] _image Image to publish
   * \param[in] _width Image width
   * \param[in] _height Image height
   * \param[in] camera_num Index number of camera
   */
  void NewFrame(
    const unsigned char * _image,
    unsigned int _width, unsigned int _height,
    int camera_num);

  /*
   * \details This is called at the camera's update rate.
   * \details Not called when the camera isn't active. For a triggered camera, it will only be
   * called after triggered.
   * \param[in] _image Image
   * \param[in] _width Image width
   * \param[in] _height Image height
   * \param[in] _depth Image depth
   * \param[in] _format Image format
   */
  void OnNewFrame(
    const unsigned char * _image,
    unsigned int _width, unsigned int _height,
    unsigned int _depth, const std::string & _format) override;

  /*
  * \details This is called at the camera's update rate.
  * \details Not called when the camera isn't active. For a triggered camera, it will only be
  * called after triggered.
  * \param[in] _image Image
  * \param[in] _width Image width
  * \param[in] _height Image height
  * \param[in] _depth Image depth
  * \param[in] _format Image format
  */
  void OnNewImageFrame(
    const unsigned char * _image,
    unsigned int _width, unsigned int _height,
    unsigned int _depth, const std::string & _format) override;

  /*
  * \details This is called at the camera's update rate.
  * \details Not called when the camera isn't active. For a triggered camera, it will only be
  * called after triggered.
  * \param[in] _image Image
  * \param[in] _width Image width
  * \param[in] _height Image height
  * \param[in] _depth Image depth
  * \param[in] _format Image format
  */
  void OnNewDepthFrame(
    const float * _image,
    unsigned int _width, unsigned int _height,
    unsigned int _depth, const std::string & _format) override;


  /*
  * \details This is called at the multi camera's update rate.
  * \details Not called when the camera isn't active. For a triggered multi camera, it will only be
  * called after triggered.
  * \param[in] _image Image
  * \param[in] _width Image width
  * \param[in] _height Image height
  * \param[in] _depth Image depth
  * \param[in] _format Image format
  * \param[in] _camera_num Index number of camera
  */
  void OnNewMultiFrame(
    const unsigned char * _image,
    unsigned int _width, unsigned int _height,
    unsigned int _depth, const std::string & _format, const int _camera_num) override;

  void OnTrigger(const std_msgs::msg::Empty::SharedPtr _dummy);

  void PreRender();

  void SetCameraEnabled(const bool _enabled);

  // Get pointer to the cameras
  std::vector<gazebo::rendering::CameraPtr> GetCameras() const;

  // Get camera name
  std::string GetCameraName() const;

  // Get number of cameras
  uint64_t GetNumCameras() const;

  gazebo_ros::Node::SharedPtr GetRosNode() const;

private:
  std::unique_ptr<GazeboRosCameraPrivate> impl_;

  // A handler for the param change callback.
  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_change_callback_handler_;
};
}  // namespace gazebo_plugins

#endif  // GAZEBO_PLUGINS__GAZEBO_ROS_CAMERA_HPP_