Classes | Macros | Typedefs | Variables
camera.h File Reference
#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>
Include dependency graph for camera.h:
This graph shows which files directly or indirectly include this file:

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.
 

Macro Definition Documentation

#define FINISH_NXLIB_ACTION (   ACTION_NAME)
Value:
} /* NOLINT */ \
catch (NxLibException & e) \
{ \
ROS_ERROR("NxLibException %d (%s) for item %s", e.getErrorCode(), e.getErrorText().c_str(), \
e.getItemPath().c_str()); \
ensenso_camera_msgs::ACTION_NAME##Result result; \
result.error.code = e.getErrorCode(); \
result.error.message = e.getErrorText(); \
server->setAborted(result); \
return; \
} /* NOLINT */ \
{ \
ROS_ERROR("TF Exception: %s", e.what()); \
ensenso_camera_msgs::ACTION_NAME##Result result; \
result.error.code = ERROR_CODE_TF; \
result.error.message = e.what(); \
server->setAborted(result); \
return; \
} /* NOLINT */ \
catch (std::exception & e) \
{ \
ROS_ERROR("Unknown Exception: %s", e.what()); \
ensenso_camera_msgs::ACTION_NAME##Result result; \
result.error.code = ERROR_CODE_UNKNOWN_EXCEPTION; \
result.error.message = e.what(); \
server->setAborted(result); \
return; \
}
int const ERROR_CODE_UNKNOWN_EXCEPTION
Definition: camera.h:66
#define LOG_NXLIB_EXCEPTION(EXCEPTION)
Definition: camera.h:69
int const ERROR_CODE_TF
Definition: camera.h:67

Definition at line 102 of file camera.h.

#define LOG_NXLIB_EXCEPTION (   EXCEPTION)
Value:
try \
{ \
if (EXCEPTION.getErrorCode() == NxLibExecutionFailed) \
{ \
NxLibItem executionNode(EXCEPTION.getItemPath()); \
ROS_ERROR("%s: %s", executionNode[itmResult][itmErrorSymbol].asString().c_str(), \
executionNode[itmResult][itmErrorText].asString().c_str()); \
} /* NOLINT */ \
} /* NOLINT */ \
catch (...) \
{ \
} /* NOLINT */ \
ROS_DEBUG("Current NxLib tree: %s", NxLibItem().asJson(true).c_str());

Definition at line 69 of file camera.h.

#define PREEMPT_ACTION_IF_REQUESTED
Value:
if (server->isPreemptRequested()) \
{ \
server->setPreempted(); \
return; \
}

Definition at line 134 of file camera.h.

#define START_NXLIB_ACTION (   ACTION_NAME,
  ACTION_SERVER 
)
Value:
ROS_DEBUG("Received a " #ACTION_NAME " request."); \
auto& server = ACTION_SERVER; \
if (server->isPreemptRequested()) \
{ \
server->setPreempted(); \
return; \
} /* NOLINT */ \
std::lock_guard<std::mutex> lock(nxLibMutex); \
try \
{
#define ROS_DEBUG(...)

Definition at line 91 of file camera.h.

Typedef Documentation

using AccessTreeServer = QueuedActionServer<ensenso_camera_msgs::AccessTreeAction>

Definition at line 141 of file camera.h.

using ExecuteCommandServer = QueuedActionServer<ensenso_camera_msgs::ExecuteCommandAction>

Definition at line 142 of file camera.h.

using GetParameterServer = QueuedActionServer<ensenso_camera_msgs::GetParameterAction>

Definition at line 143 of file camera.h.

using SetParameterServer = QueuedActionServer<ensenso_camera_msgs::SetParameterAction>

Definition at line 144 of file camera.h.

Variable Documentation

std::string const DEFAULT_PARAMETER_SET = "default"

The name of the parameter set that is used when an action was not given a parameter set explicitly.

Definition at line 57 of file camera.h.

int const ERROR_CODE_TF = 101

Definition at line 67 of file camera.h.

int const ERROR_CODE_UNKNOWN_EXCEPTION = 100

Definition at line 66 of file camera.h.

double const POSE_TF_INTERVAL = 1

The interval at which we publish the current tf transfrom from the camera to the target frame, if a target frame is available.

Definition at line 46 of file camera.h.

double const STATUS_INTERVAL = 3.0

The interval at which we publish diagnostic messages containing the camera status.

Definition at line 40 of file camera.h.

std::string const TARGET_FRAME_LINK = "Workspace"

The name of the target frame in the NxLib.

Definition at line 62 of file camera.h.

double const TRANSFORMATION_REQUEST_TIMEOUT = 10.

The maximum time that we wait for a tf transformation to become available.

Definition at line 51 of file camera.h.



ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:06