#include <stereo_camera.h>
|
void | onCalibrateHandEye (ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const &goal) |
|
void | onCalibrateWorkspace (ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const &goal) |
|
void | onFitPrimitive (ensenso_camera_msgs::FitPrimitiveGoalConstPtr const &goal) |
|
void | onLocatePattern (ensenso_camera_msgs::LocatePatternGoalConstPtr const &goal) |
|
void | onProjectPattern (ensenso_camera_msgs::ProjectPatternGoalConstPtr const &goal) |
|
void | onRequestData (ensenso_camera_msgs::RequestDataGoalConstPtr const &goal) |
|
void | onSetParameter (ensenso_camera_msgs::SetParameterGoalConstPtr const &goal) override |
|
void | onTelecentricProjection (ensenso_camera_msgs::TelecentricProjectionGoalConstPtr const &goal) |
|
void | onTexturedPointCloud (ensenso_camera_msgs::TexturedPointCloudGoalConstPtr const &goal) |
|
bool | open () override |
|
void | startServers () const override |
|
| StereoCamera (ros::NodeHandle nh, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string robotFrame, std::string wristFrame, std::string linkFrame, int captureTimeout, std::unique_ptr< ensenso_camera::VirtualObjectHandler > virtualObjectHandler=nullptr) |
|
| Camera (ros::NodeHandle const &n, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame) |
|
void | close () |
|
virtual void | initStatusTimer () |
|
virtual void | initTfPublishTimer () |
|
bool | loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false) |
|
void | onAccessTree (ensenso_camera_msgs::AccessTreeGoalConstPtr const &goal) |
|
void | onExecuteCommand (ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &goal) |
|
void | onGetParameter (ensenso_camera_msgs::GetParameterGoalConstPtr const &goal) |
|
Definition at line 33 of file stereo_camera.h.
StereoCamera::StereoCamera |
( |
ros::NodeHandle |
nh, |
|
|
std::string |
serial, |
|
|
std::string |
fileCameraPath, |
|
|
bool |
fixed, |
|
|
std::string |
cameraFrame, |
|
|
std::string |
targetFrame, |
|
|
std::string |
robotFrame, |
|
|
std::string |
wristFrame, |
|
|
std::string |
linkFrame, |
|
|
int |
captureTimeout, |
|
|
std::unique_ptr< ensenso_camera::VirtualObjectHandler > |
virtualObjectHandler = nullptr |
|
) |
| |
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implements Camera.
Definition at line 1147 of file stereo_camera.cpp.
Try to collect patterns on the current images. For the command to be successful, the patterns must be decodable and visible in both cameras.
Definition at line 1186 of file stereo_camera.cpp.
void StereoCamera::fillCameraInfoFromNxLib |
( |
sensor_msgs::CameraInfoPtr const & |
info, |
|
|
bool |
right, |
|
|
bool |
rectified = false |
|
) |
| const |
|
private |
Read the camera calibration from the NxLib and write it into a CameraInfo message.
- Parameters
-
info | The CameraInfo message to which the calibration should be written. |
right | Whether to use the calibration from the right camera instead of the left one. |
Definition at line 1265 of file stereo_camera.cpp.
Load the parameter set with the given name. If it does not exist yet, it will be created by copying the current default parameters.
The projector and front light will be enabled according to the given flag, unless they have been manually enabled or disabled for the current parameter set.
Definition at line 1110 of file stereo_camera.cpp.
void StereoCamera::onCalibrateHandEye |
( |
ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onCalibrateWorkspace |
( |
ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onFitPrimitive |
( |
ensenso_camera_msgs::FitPrimitiveGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onLocatePattern |
( |
ensenso_camera_msgs::LocatePatternGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onProjectPattern |
( |
ensenso_camera_msgs::ProjectPatternGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onRequestData |
( |
ensenso_camera_msgs::RequestDataGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onSetParameter |
( |
ensenso_camera_msgs::SetParameterGoalConstPtr const & |
goal | ) |
|
|
overridevirtual |
void StereoCamera::onTelecentricProjection |
( |
ensenso_camera_msgs::TelecentricProjectionGoalConstPtr const & |
goal | ) |
|
void StereoCamera::onTexturedPointCloud |
( |
ensenso_camera_msgs::TexturedPointCloudGoalConstPtr const & |
goal | ) |
|
bool StereoCamera::open |
( |
| ) |
|
|
overridevirtual |
ensenso_camera_msgs::ParameterPtr StereoCamera::readParameter |
( |
std::string const & |
key | ) |
const |
|
overrideprivatevirtual |
void StereoCamera::saveParameterSet |
( |
std::string |
name, |
|
|
bool |
projectorWasSet |
|
) |
| |
|
private |
Save the current settings to the parameter set with the given name.
If the projector or front light have been enabled or disabled manually, the flag should be set. It then disabled the automatic control of the projector and front light for this parameter set.
Definition at line 1094 of file stereo_camera.cpp.
void StereoCamera::startServers |
( |
| ) |
const |
|
overridevirtual |
Start the action servers. The camera must already be open, otherwise the actions might access parts of the NxLib that are not initialized yet.
Reimplemented from Camera.
Definition at line 74 of file stereo_camera.cpp.
void StereoCamera::updateCameraInfo |
( |
| ) |
|
|
overrideprivatevirtual |
Update the cached CameraInfo messages that will be published together with the images.
Implements Camera.
Definition at line 1343 of file stereo_camera.cpp.
void StereoCamera::writeParameter |
( |
ensenso_camera_msgs::Parameter const & |
parameter | ) |
|
|
overrideprivatevirtual |
int StereoCamera::captureTimeout |
|
private |
std::string StereoCamera::handEyeCalibrationPatternBuffer |
|
private |
std::vector<tf2::Transform> StereoCamera::handEyeCalibrationRobotPoses |
|
private |
sensor_msgs::CameraInfoPtr StereoCamera::leftCameraInfo |
|
private |
sensor_msgs::CameraInfoPtr StereoCamera::leftRectifiedCameraInfo |
|
private |
sensor_msgs::CameraInfoPtr StereoCamera::rightCameraInfo |
|
private |
sensor_msgs::CameraInfoPtr StereoCamera::rightRectifiedCameraInfo |
|
private |
std::string StereoCamera::robotFrame |
|
private |
std::string StereoCamera::wristFrame |
|
private |
The documentation for this class was generated from the following files: