ros2_control - humble
Loading...
Searching...
No Matches
mujoco_cameras.hpp
1
20#pragma once
21
22#include <atomic>
23#include <mutex>
24#include <thread>
25#include <vector>
26
27#include <GLFW/glfw3.h>
28#include <mujoco/mujoco.h>
29
30#include <hardware_interface/hardware_info.hpp>
31#include <rclcpp/node.hpp>
32#include <rclcpp/publisher.hpp>
33#include <rclcpp/rclcpp.hpp>
34#include <sensor_msgs/msg/camera_info.hpp>
35#include <sensor_msgs/msg/image.hpp>
36
37namespace mujoco_ros2_control
38{
39
41{
42 mjvCamera mjv_cam;
43 mjrRect viewport;
44
45 std::string name;
46 std::string frame_name;
47 std::string info_topic;
48 std::string image_topic;
49 std::string depth_topic;
50
51 uint32_t width;
52 uint32_t height;
53
54 std::vector<uint8_t> image_buffer;
55 std::vector<float> depth_buffer;
56 std::vector<float> depth_buffer_flipped;
57
58 sensor_msgs::msg::Image image;
59 sensor_msgs::msg::Image depth_image;
60 sensor_msgs::msg::CameraInfo camera_info;
61
62 rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr image_pub;
63 rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr depth_image_pub;
64 rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_pub;
65};
66
71{
72public:
82 explicit MujocoCameras(rclcpp::Node::SharedPtr node, std::recursive_mutex* sim_mutex, mjData* mujoco_data,
83 mjModel* mujoco_model, double camera_publish_rate);
84
91 void init();
92
96 void close();
97
101 void register_cameras(const hardware_interface::HardwareInfo& hardware_info);
102
103private:
107 void update_loop();
108
112 void update();
113
114 rclcpp::Node::SharedPtr node_;
115
116 // Ensures locked access to simulation data for rendering.
117 std::recursive_mutex* sim_mutex_{ nullptr };
118
119 mjData* mj_data_;
120 mjModel* mj_model_;
121 mjData* mj_camera_data_;
122
123 // Image publishing rate
124 double camera_publish_rate_;
125
126 // Rendering options for the cameras, currently hard coded to defaults
127 mjvOption mjv_opt_;
128 mjvScene mjv_scn_;
129 mjrContext mjr_con_;
130
131 // Containers for camera data and ROS constructs
132 std::vector<CameraData> cameras_;
133
134 // Camera processing thread
135 std::thread rendering_thread_;
136 std::atomic_bool publish_images_;
137};
138
139} // namespace mujoco_ros2_control
Wraps MuJoCo cameras for publishing ROS 2 RGB-D streams.
Definition mujoco_cameras.hpp:71
void register_cameras(const hardware_interface::HardwareInfo &hardware_info)
Parses camera information from the mujoco model.
Definition mujoco_cameras.cpp:40
void close()
Stops the camera processing thread and closes the relevant objects, call before shutdown.
Definition mujoco_cameras.cpp:144
void init()
Starts the image processing thread in the background.
Definition mujoco_cameras.cpp:131
Definition data.hpp:31
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:106
Definition mujoco_cameras.hpp:41