#include <mono_camera.h>
|
ros::Time | capture () const override |
|
| MonoCamera (ros::NodeHandle nh, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame) |
|
void | onLocatePattern (ensenso_camera_msgs::LocatePatternMonoGoalConstPtr const &goal) |
|
void | onRequestData (ensenso_camera_msgs::RequestDataMonoGoalConstPtr const &goal) |
|
void | onSetParameter (ensenso_camera_msgs::SetParameterGoalConstPtr const &goal) override |
|
bool | open () override |
|
void | startServers () const override |
|
| 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 11 of file mono_camera.h.
MonoCamera::MonoCamera |
( |
ros::NodeHandle |
nh, |
|
|
std::string |
serial, |
|
|
std::string |
fileCameraPath, |
|
|
bool |
fixed, |
|
|
std::string |
cameraFrame, |
|
|
std::string |
targetFrame, |
|
|
std::string |
linkFrame |
|
) |
| |
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implements Camera.
Definition at line 24 of file mono_camera.cpp.
geometry_msgs::TransformStamped MonoCamera::estimatePatternPose |
( |
ros::Time |
imageTimestamp = ros::Time::now() , |
|
|
std::string const & |
targetFrame = "" , |
|
|
bool |
latestPatternOnly = false |
|
) |
| const |
|
overrideprivatevirtual |
Estimate the pose of a pattern in the given TF frame. The pattern must already be contained in the pattern buffer (that is, you should call collectPattern before this function).
When the latestPatternOnly flag is set, the estimated position will be the one of the latest pattern in the buffer. Otherwise the function assumes that all observations are of the same pattern. It will then average their positions to increase the accuracy of the pose estimation.
Reimplemented from Camera.
Definition at line 379 of file mono_camera.cpp.
std::vector< geometry_msgs::TransformStamped > MonoCamera::estimatePatternPoses |
( |
ros::Time |
imageTimestamp = ros::Time::now() , |
|
|
std::string const & |
targetFrame = "" |
|
) |
| const |
|
overrideprivatevirtual |
Estimate the pose of each pattern in the pattern buffer for mono cameras.
Reimplemented from Camera.
Definition at line 406 of file mono_camera.cpp.
void MonoCamera::fillCameraInfoFromNxLib |
( |
sensor_msgs::CameraInfoPtr const & |
info, |
|
|
bool |
rectified = false |
|
) |
| |
|
private |
void MonoCamera::onLocatePattern |
( |
ensenso_camera_msgs::LocatePatternMonoGoalConstPtr const & |
goal | ) |
|
void MonoCamera::onRequestData |
( |
ensenso_camera_msgs::RequestDataMonoGoalConstPtr const & |
goal | ) |
|
void MonoCamera::onSetParameter |
( |
ensenso_camera_msgs::SetParameterGoalConstPtr const & |
goal | ) |
|
|
overridevirtual |
bool MonoCamera::open |
( |
| ) |
|
|
overridevirtual |
void MonoCamera::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 96 of file mono_camera.cpp.
void MonoCamera::updateCameraInfo |
( |
| ) |
|
|
overrideprivatevirtual |
Update the cached CameraInfo messages that will be published together with the images.
Implements Camera.
Definition at line 58 of file mono_camera.cpp.
sensor_msgs::CameraInfoPtr MonoCamera::cameraInfo |
|
private |
sensor_msgs::CameraInfoPtr MonoCamera::rectifiedCameraInfo |
|
private |
The documentation for this class was generated from the following files: