29 #include <sensor_msgs/Image.h> 32 #include <std_msgs/Empty.h> 34 #include <std_srvs/Empty.h> 46 #include <dynamic_reconfigure/server.h> 47 #include <rtabmap_ros/CameraConfig.h> 55 unsigned int imageWidth = 0,
56 unsigned int imageHeight = 0) :
97 bool startSrv(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
107 bool stopSrv(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
117 void setParameters(
int deviceId,
double frameRate,
const std::string & path,
bool pause)
119 ROS_INFO(
"Parameters changed: deviceId=%d, path=%s frameRate=%f pause=%s",
120 deviceId, path.c_str(), frameRate, pause?
"true":
"false");
149 if(!path.empty() && path.compare(videoCam->
getFilePath()) == 0)
162 else if(path.empty() &&
207 ROS_ERROR(
"Path \"%s\" does not exist (or you don't have the permissions to read)... falling back to usb device...", path.c_str());
228 if(!image.empty() && image.depth() == CV_8U)
231 if(image.channels() == 1)
240 sensor_msgs::ImagePtr rosMsg = img.
toImageMsg();
263 camera->
setParameters(config.device_id, config.frame_rate, config.video_or_images_path, config.pause);
267 int main(
int argc,
char** argv)
279 dynamic_reconfigure::Server<rtabmap_ros::CameraConfig>
server;
280 dynamic_reconfigure::Server<rtabmap_ros::CameraConfig>::CallbackType
f;
282 server.setCallback(f);
image_transport::Publisher rosPublisher_
void setParameters(int deviceId, double frameRate, const std::string &path, bool pause)
int main(int argc, char **argv)
static std::string getDir(const std::string &filePath)
ros::ServiceServer stopSrv_
void setImageRate(float imageRate)
GLM_FUNC_DECL genType e()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer startSrv_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const cv::Mat & imageRaw() const
rtabmap::CameraThread * cameraThread_
ROSCPP_DECL void spin(Spinner &spinner)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
rtabmap::Camera * camera_
void publish(const sensor_msgs::Image &message) const
virtual std::string getClassName() const =0
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
CameraWrapper(int usbDevice=0, float imageRate=0, unsigned int imageWidth=0, unsigned int imageHeight=0)
static void setEventLevel(ULogger::Level eventSentLevel)
void callback(rtabmap_ros::CameraConfig &config, uint32_t level)
static void addHandler(UEventsHandler *handler)
bool startSrv(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
static bool exists(const std::string &dirPath)
std::string getPath() const
const SensorData & data() const
const std::string & getFilePath() const
void join(bool killFirst=false)
bool stopSrv(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual bool handleEvent(UEvent *event)
sensor_msgs::ImagePtr toImageMsg() const