37 #include <rc_genicam_api/config.h> 42 std::function<
void()>& sub_changed)
51 info.distortion_model =
"plumb_bob";
97 pub = nh.
advertise<sensor_msgs::CameraInfo>(
"left/camera_info", 1,
105 pub = nh.
advertise<sensor_msgs::CameraInfo>(
"right/camera_info", 1,
133 info.header.stamp.sec = time / 1000000000ul;
134 info.header.stamp.nsec = time % 1000000000ul;
136 info.width =
static_cast<uint32_t
>(buffer->
getWidth(part));
137 info.height =
static_cast<uint32_t
>(buffer->
getHeight(part));
Interface for all publishers relating to images, point clouds or other stereo-camera data...
std::function< void()> sub_callback
size_t getWidth(std::uint32_t part) const
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
static const int ComponentIntensity
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
CameraInfoPublisher(ros::NodeHandle &nh, const std::string &frame_id, bool left, std::function< void()> &sub_changed)
Initialization of publisher.
void publish(const boost::shared_ptr< M > &message) const
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
size_t getHeight(std::uint32_t part) const
uint64_t getTimestampNS() const
bool used() override
Returns true if there are subscribers to the topic.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
sensor_msgs::CameraInfo info
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.