#include <mono_camera.h>
Public Member Functions | |
ensenso::ros::Time | capture () const override |
void | init () override |
MonoCamera (ensenso::ros::NodeHandle &nh, CameraParameters params) | |
void | onLocatePattern (ensenso::action::LocatePatternMonoGoalConstPtr const &goal) |
void | onRequestData (ensenso::action::RequestDataMonoGoalConstPtr const &goal) |
void | onSetParameter (ensenso::action::SetParameterGoalConstPtr const &goal) override |
![]() | |
Camera (ensenso::ros::NodeHandle &nh, CameraParameters params) | |
void | close () |
bool | loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false) |
void | onAccessTree (ensenso::action::AccessTreeGoalConstPtr const &goal) |
void | onExecuteCommand (ensenso::action::ExecuteCommandGoalConstPtr const &goal) |
void | onGetParameter (ensenso::action::GetParameterGoalConstPtr const &goal) |
bool | open () |
virtual void | updateCameraTypeSpecifics () |
Private Member Functions | |
void | advertiseTopics () |
std::vector< MonoCalibrationPattern > | collectPattern (bool clearBuffer=false) const |
geometry_msgs::msg::PoseStamped | estimatePatternPose (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="", bool latestPatternOnly=false) const override |
std::vector< geometry_msgs::msg::PoseStamped > | estimatePatternPoses (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="") const override |
void | fillCameraInfoFromNxLib (sensor_msgs::msg::CameraInfoPtr const &info, bool rectified=false) |
void | startServers () const override |
void | updateCameraInfo () override |
Private Attributes | |
sensor_msgs::msg::CameraInfoPtr | cameraInfo |
std::unique_ptr< LocatePatternMonoServer > | locatePatternServer |
image_transport::CameraPublisher | rawImagePublisher |
sensor_msgs::msg::CameraInfoPtr | rectifiedCameraInfo |
image_transport::CameraPublisher | rectifiedImagePublisher |
std::unique_ptr< RequestDataMonoServer > | requestDataServer |
Additional Inherited Members | |
![]() | |
bool | cameraIsAvailable () const |
bool | cameraIsOpen () const |
void | fillBasicCameraInfoFromNxLib (sensor_msgs::msg::CameraInfoPtr const &info) const |
tf2::Transform | getCameraToLinkTransform () |
std::string | getNxLibTargetFrameName () const |
bool | hasLink () const |
virtual void | initStatusTimer () |
virtual void | initTfPublishTimer () |
void | loadParameterSet (std::string name) |
void | publishCameraLink () |
void | publishCurrentLinks (TIMER_CALLBACK_DECLARATION_ARGS) |
void | publishStatus (TIMER_CALLBACK_DECLARATION_ARGS) |
virtual ensenso::msg::ParameterPtr | readParameter (std::string const &key) const |
void | saveDefaultParameterSet () |
void | saveParameterSet (std::string name) |
geometry_msgs::msg::TransformStamped | stampedLinkToCamera () |
void | updateGlobalLink (ensenso::ros::Time time, std::string targetFrame="", bool useCachedTransformation=false) const |
void | updateTransformations (tf2::Transform const &targetFrameTransformation) const |
virtual void | writeParameter (ensenso::msg::Parameter const ¶meter) |
![]() | |
std::unique_ptr< AccessTreeServer > | accessTreeServer |
NxLibItem | cameraNode |
ensenso::ros::Timer | cameraPosePublisher |
bool | createdFileCamera = false |
std::string | currentParameterSet |
NxLibItem | defaultParameters |
std::unique_ptr< ExecuteCommandServer > | executeCommandServer |
std::unique_ptr< GetParameterServer > | getParameterServer |
ensenso::ros::NodeHandle | nh |
std::mutex | nxLibMutex |
NxLibVersion | nxLibVersion |
std::map< std::string, ParameterSet > | parameterSets |
CameraParameters | params |
std::unique_ptr< SetParameterServer > | setParameterServer |
ensenso::ros::Publisher< diagnostic_msgs::msg::DiagnosticArray > | statusPublisher |
ensenso::ros::Timer | statusTimer |
std::unique_ptr< tf2_ros::Buffer > | tfBuffer |
std::map< std::string, geometry_msgs::msg::TransformStamped > | transformationCache |
std::unique_ptr< tf2_ros::TransformBroadcaster > | transformBroadcaster |
std::unique_ptr< tf2_ros::TransformListener > | transformListener |
Definition at line 9 of file mono_camera.h.
MonoCamera::MonoCamera | ( | ensenso::ros::NodeHandle & | nh, |
CameraParameters | params | ||
) |
Definition at line 5 of file mono_camera.cpp.
|
private |
Advertise all camera topics.
Definition at line 14 of file mono_camera.cpp.
|
overridevirtual |
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implements Camera.
Definition at line 35 of file mono_camera.cpp.
|
private |
Runs the NxLib's collectPattern command and returns a vector of MonoCalibrationPatterns. The result is empty if no pattern was found or if the pattern is / patterns are not decodable. Otherwise the result contains the found patterns.
Definition at line 326 of file mono_camera.cpp.
|
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.
Implements Camera.
Definition at line 379 of file mono_camera.cpp.
|
overrideprivatevirtual |
Estimate the pose of each pattern in the pattern buffer.
Implements Camera.
Definition at line 407 of file mono_camera.cpp.
|
private |
Read the camera calibration from the NxLib and write it into a CameraInfo message.
Definition at line 70 of file mono_camera.cpp.
|
overridevirtual |
void MonoCamera::onLocatePattern | ( | ensenso::action::LocatePatternMonoGoalConstPtr const & | goal | ) |
Callback for the locate_pattern
action.
Definition at line 220 of file mono_camera.cpp.
void MonoCamera::onRequestData | ( | ensenso::action::RequestDataMonoGoalConstPtr const & | goal | ) |
Callback for the request_data
action.
Definition at line 99 of file mono_camera.cpp.
|
overridevirtual |
Callback for the set_parameter
action.
Implements Camera.
Definition at line 175 of file mono_camera.cpp.
|
overrideprivatevirtual |
Start the action servers. The camera must already be opened, otherwise the actions might access parts of the NxLib that are not initialized yet.
Reimplemented from Camera.
Definition at line 28 of file mono_camera.cpp.
|
overrideprivatevirtual |
Update the cached CameraInfo messages that will be published together with the images.
Implements Camera.
Definition at line 64 of file mono_camera.cpp.
|
private |
Definition at line 12 of file mono_camera.h.
|
private |
Definition at line 16 of file mono_camera.h.
|
private |
Definition at line 18 of file mono_camera.h.
|
private |
Definition at line 13 of file mono_camera.h.
|
private |
Definition at line 19 of file mono_camera.h.
|
private |
Definition at line 15 of file mono_camera.h.