Go to the documentation of this file.
28 void onSetParameter(ensenso::action::SetParameterGoalConstPtr
const& goal)
override;
33 void onRequestData(ensenso::action::RequestDataMonoGoalConstPtr
const& goal);
38 void onLocatePattern(ensenso::action::LocatePatternMonoGoalConstPtr
const& goal);
46 std::string
const& targetFrame =
"",
47 bool latestPatternOnly =
false)
const override;
50 std::string
const& targetFrame =
"")
const override;
67 std::vector<MonoCalibrationPattern>
collectPattern(
bool clearBuffer =
false)
const;
void onSetParameter(ensenso::action::SetParameterGoalConstPtr const &goal) override
void startServers() const override
std::unique_ptr< RequestDataMonoServer > requestDataServer
geometry_msgs::msg::PoseStamped estimatePatternPose(ensenso::ros::Time imageTimestamp, std::string const &targetFrame="", bool latestPatternOnly=false) const override
ensenso::ros::Time capture() const override
std::vector< MonoCalibrationPattern > collectPattern(bool clearBuffer=false) const
void updateCameraInfo() override
void onRequestData(ensenso::action::RequestDataMonoGoalConstPtr const &goal)
sensor_msgs::msg::CameraInfoPtr rectifiedCameraInfo
image_transport::CameraPublisher rawImagePublisher
std::unique_ptr< LocatePatternMonoServer > locatePatternServer
::ros::NodeHandle NodeHandle
image_transport::CameraPublisher rectifiedImagePublisher
void onLocatePattern(ensenso::action::LocatePatternMonoGoalConstPtr const &goal)
void fillCameraInfoFromNxLib(sensor_msgs::msg::CameraInfoPtr const &info, bool rectified=false)
std::vector< geometry_msgs::msg::PoseStamped > estimatePatternPoses(ensenso::ros::Time imageTimestamp, std::string const &targetFrame="") const override
sensor_msgs::msg::CameraInfoPtr cameraInfo
MonoCamera(ensenso::ros::NodeHandle &nh, CameraParameters params)
ensenso::ros::NodeHandle nh
ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46