#include "ensenso_camera_msgs/AccessTreeAction.h"#include "ensenso_camera_msgs/CalibrateHandEyeAction.h"#include "ensenso_camera_msgs/CalibrateWorkspaceAction.h"#include "ensenso_camera_msgs/ExecuteCommandAction.h"#include "ensenso_camera_msgs/FitPrimitiveAction.h"#include "ensenso_camera_msgs/GetParameterAction.h"#include "ensenso_camera_msgs/SetParameterAction.h"#include "ensenso_camera/calibration_pattern.h"#include "ensenso_camera/point_cloud_utilities.h"#include "ensenso_camera/queued_action_server.h"#include "ensenso_camera/image_utilities.h"#include "ensenso_camera/nxLibVersionInfo.h"#include "nxLib.h"#include <tf2/LinearMath/Transform.h>#include <image_transport/image_transport.h>#include <ros/ros.h>#include <sensor_msgs/CameraInfo.h>#include <tf2_ros/transform_listener.h>#include <tf2_ros/transform_broadcaster.h>#include <tf2_ros/static_transform_broadcaster.h>#include <geometry_msgs/TransformStamped.h>#include <tf2/LinearMath/Quaternion.h>#include <diagnostic_msgs/DiagnosticArray.h>#include <map>#include <memory>#include <mutex>#include <string>#include <vector>#include <fstream>

Go to the source code of this file.
Classes | |
| class | Camera |
| struct | ParameterSet |
Macros | |
| #define | FINISH_NXLIB_ACTION(ACTION_NAME) |
| #define | LOG_NXLIB_EXCEPTION(EXCEPTION) |
| #define | PREEMPT_ACTION_IF_REQUESTED |
| #define | START_NXLIB_ACTION(ACTION_NAME, ACTION_SERVER) |
Typedefs | |
| using | AccessTreeServer = QueuedActionServer< ensenso_camera_msgs::AccessTreeAction > |
| using | ExecuteCommandServer = QueuedActionServer< ensenso_camera_msgs::ExecuteCommandAction > |
| using | GetParameterServer = QueuedActionServer< ensenso_camera_msgs::GetParameterAction > |
| using | SetParameterServer = QueuedActionServer< ensenso_camera_msgs::SetParameterAction > |
Variables | |
| std::string const | DEFAULT_PARAMETER_SET = "default" |
| int const | ERROR_CODE_TF = 101 |
| int const | ERROR_CODE_UNKNOWN_EXCEPTION = 100 |
| double const | POSE_TF_INTERVAL = 1 |
| double const | STATUS_INTERVAL = 3.0 |
| std::string const | TARGET_FRAME_LINK = "Workspace" |
| double const | TRANSFORMATION_REQUEST_TIMEOUT = 10. |
| #define FINISH_NXLIB_ACTION | ( | ACTION_NAME | ) |
| #define LOG_NXLIB_EXCEPTION | ( | EXCEPTION | ) |
| #define PREEMPT_ACTION_IF_REQUESTED |
| #define START_NXLIB_ACTION | ( | ACTION_NAME, | |
| ACTION_SERVER | |||
| ) |
| using AccessTreeServer = QueuedActionServer<ensenso_camera_msgs::AccessTreeAction> |
| using ExecuteCommandServer = QueuedActionServer<ensenso_camera_msgs::ExecuteCommandAction> |
| using GetParameterServer = QueuedActionServer<ensenso_camera_msgs::GetParameterAction> |
| using SetParameterServer = QueuedActionServer<ensenso_camera_msgs::SetParameterAction> |
| std::string const DEFAULT_PARAMETER_SET = "default" |
| double const POSE_TF_INTERVAL = 1 |
| double const STATUS_INTERVAL = 3.0 |
| std::string const TARGET_FRAME_LINK = "Workspace" |