35 #include <sensor_msgs/CameraInfo.h>    38 int main(
int argc, 
char** argv)
    43         ros::init(argc, argv, 
"uvc_stereo_camera");
    47         std::string 
id = 
"camera";
    48         std::string 
frameId = 
"camera_link";
    50         pnh.
param(
"rate", rate, rate);
    51         pnh.
param(
"camera_id", 
id, 
id);
    52         pnh.
param(
"frame_id", frameId, frameId);
    53         pnh.
param(
"scale", scale, scale);
    78                         imageLeft.
header.stamp = currentTime;
    91                                 sensor_msgs::CameraInfo infoLeft, infoRight;
    94                                 infoLeft.header = imageLeft.
header;
    95                                 infoRight.header = imageLeft.
header;
    97                                 infoRightPub.publish(infoRight);
   109                 ROS_ERROR(
"Could not initialize the camera!");
 static std::string homeDir()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
const std::vector< StereoCameraModel > & stereoCameraModels() const
static void setLevel(ULogger::Level level)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
SensorData takeImage(CameraInfo *info=0)
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
const cv::Mat & imageRaw() const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
std::string resolveName(const std::string &name, bool remap=true) const
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()