Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Frame callbacks #160

Merged
merged 6 commits into from
Dec 15, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 7 additions & 10 deletions realsense_camera/include/realsense_camera/base_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ namespace realsense_camera
// Interfaces.
virtual void onInit();
virtual ~BaseNodelet();
virtual void prepareTopics();
virtual void setDepthEnable(bool &enable_depth);
virtual bool getCameraOptionValues(realsense_camera::CameraConfiguration::Request & req,
realsense_camera::CameraConfiguration::Response & res);
virtual bool setPowerCameraService(realsense_camera::SetPower::Request & req,
Expand Down Expand Up @@ -113,7 +113,7 @@ namespace realsense_camera
std::string usb_port_id_;
std::string camera_type_;
std::string mode_;
bool enable_[STREAM_COUNT];
bool enable_[STREAM_COUNT] = {false};
int width_[STREAM_COUNT];
int height_[STREAM_COUNT];
int fps_[STREAM_COUNT];
Expand All @@ -132,13 +132,9 @@ namespace realsense_camera
float max_z_ = -1.0f;
bool enable_pointcloud_;
bool enable_tf_;
bool duplicate_depth_color_;
const uint16_t *image_depth16_;
boost::shared_ptr<boost::thread> topic_thread_;
float depth_scale_meters_;
cv::Mat cvWrapper_;
bool start_camera_ = true;
bool start_stop_srv_called_ = false;
boost::mutex frame_mutex_[STREAM_COUNT];

struct CameraOptions
{
Expand All @@ -165,14 +161,15 @@ namespace realsense_camera
virtual void disableStream(rs_stream stream_index);
virtual std::string startCamera();
virtual std::string stopCamera();
virtual void publishTopics();
virtual void publishTopic(rs_stream stream_index);
virtual void getStreamData(rs_stream stream_index);
virtual void publishTopic(rs_stream stream_index, rs::frame & frame);
virtual void setImageData(rs_stream stream_index, rs::frame & frame);
virtual void publishPCTopic();
virtual void publishStaticTransforms();
virtual void checkError();
virtual bool checkForSubscriber();
virtual void wrappedSystem(std::vector<std::string> string_argv);
virtual void setFrameCallbacks();
std::function<void(rs::frame f)> depth_frame_handler_, color_frame_handler_, ir_frame_handler_;
};
}
#endif
4 changes: 2 additions & 2 deletions realsense_camera/include/realsense_camera/r200_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,9 @@ namespace realsense_camera
void setDynamicReconfigDepthControlPreset(int preset);
std::string setDynamicReconfigDepthControlIndividuals();
void configCallback(realsense_camera::r200_paramsConfig &config, uint32_t level);
void setStreams();
void publishTopics();
void publishStaticTransforms();
void setFrameCallbacks();
std::function<void(rs::frame f)> ir2_frame_handler_;
};
}
#endif
6 changes: 4 additions & 2 deletions realsense_camera/include/realsense_camera/zr300_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ namespace realsense_camera
boost::shared_ptr<boost::thread> imu_thread_;
std::function<void(rs::motion_data)> motion_handler_;
std::function<void(rs::timestamp_data)> timestamp_handler_;
boost::mutex imu_mutex_;

// Member Functions.
void getParameters();
Expand All @@ -77,11 +78,12 @@ namespace realsense_camera
void setDynamicReconfigDepthControlPreset(int preset);
std::string setDynamicReconfigDepthControlIndividuals();
void configCallback(realsense_camera::zr300_paramsConfig &config, uint32_t level);
void setStreams();
void publishTopics();
void publishStaticTransforms();
void prepareIMU();
void setIMUCallbacks();
void setFrameCallbacks();
std::function<void(rs::frame f)> fisheye_frame_handler_, ir2_frame_handler_;

};
}
#endif
Loading