Classes | Macros | Variables
camera.h File Reference
#include "ensenso_camera/calibration_pattern.h"
#include "ensenso_camera/image_utilities.h"
#include "ensenso_camera/nxlib_version.h"
#include "ensenso_camera/point_cloud_utilities.h"
#include "ensenso_camera/queued_action_server.h"
#include "ensenso_camera/string_helper.h"
#include "ensenso_camera/virtual_object_handler.h"
#include "ensenso_camera/ros2/action_server.h"
#include "ensenso_camera/ros2/core.h"
#include "ensenso_camera/ros2/logging.h"
#include "ensenso_camera/ros2/namespace.h"
#include "ensenso_camera/ros2/node_handle.h"
#include "ensenso_camera/ros2/time.h"
#include "ensenso_camera/ros2/image_transport.h"
#include "ensenso_camera/ros2/diagnostic_msgs/diagnostic_array.h"
#include "ensenso_camera/ros2/ensenso_msgs/access_tree.h"
#include "ensenso_camera/ros2/ensenso_msgs/execute_command.h"
#include "ensenso_camera/ros2/ensenso_msgs/get_parameter.h"
#include "ensenso_camera/ros2/ensenso_msgs/parameter.h"
#include "ensenso_camera/ros2/ensenso_msgs/set_parameter.h"
#include "ensenso_camera/ros2/geometry_msgs/pose_stamped.h"
#include "ensenso_camera/ros2/geometry_msgs/transform_stamped.h"
#include "ensenso_camera/ros2/sensor_msgs/camera_info.h"
#include <tf2/LinearMath/Transform.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <fstream>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <vector>
#include "nxLib.h"
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  CameraParameters
 
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)
 

Variables

const std::string DEFAULT_PARAMETER_SET = "default"
 
const int ERROR_CODE_TF = 101
 
const int ERROR_CODE_UNKNOWN_EXCEPTION = 100
 
const double POSE_TF_INTERVAL = 1
 
const double STATUS_INTERVAL = 3.0
 
const std::string TARGET_FRAME_LINK = "Workspace"
 
const double TF_REQUEST_TIMEOUT = 10.
 

Macro Definition Documentation

◆ FINISH_NXLIB_ACTION

#define FINISH_NXLIB_ACTION (   ACTION_NAME)
Value:
} /* NOLINT */ \
catch (NxLibException & e) \
{ \
ENSENSO_ERROR(nh, "NxLibException %d (%s) for item %s", e.getErrorCode(), e.getErrorText().c_str(), \
e.getItemPath().c_str()); \
LOG_NXLIB_EXCEPTION(e) \
ensenso::action::ACTION_NAME##Result result; \
result.error.code = e.getErrorCode(); \
result.error.message = e.getErrorText(); \
server->setAborted(std::move(result)); \
return; \
} /* NOLINT */ \
{ \
ENSENSO_ERROR(nh, "tf Exception: %s", e.what()); \
ensenso::action::ACTION_NAME##Result result; \
result.error.code = ERROR_CODE_TF; \
result.error.message = e.what(); \
server->setAborted(std::move(result)); \
return; \
} /* NOLINT */ \
catch (std::exception & e) \
{ \
ENSENSO_ERROR(nh, "Unknown Exception: %s", e.what()); \
ensenso::action::ACTION_NAME##Result result; \
result.error.code = ERROR_CODE_UNKNOWN_EXCEPTION; \
result.error.message = e.what(); \
server->setAborted(std::move(result)); \
return; \
}

Definition at line 104 of file camera.h.

◆ LOG_NXLIB_EXCEPTION

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

Definition at line 74 of file camera.h.

◆ PREEMPT_ACTION_IF_REQUESTED

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

Definition at line 136 of file camera.h.

◆ START_NXLIB_ACTION

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

Definition at line 93 of file camera.h.

Variable Documentation

◆ DEFAULT_PARAMETER_SET

const std::string 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 62 of file camera.h.

◆ ERROR_CODE_TF

const int ERROR_CODE_TF = 101

Definition at line 72 of file camera.h.

◆ ERROR_CODE_UNKNOWN_EXCEPTION

const int ERROR_CODE_UNKNOWN_EXCEPTION = 100

Definition at line 71 of file camera.h.

◆ POSE_TF_INTERVAL

const double POSE_TF_INTERVAL = 1

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

Definition at line 52 of file camera.h.

◆ STATUS_INTERVAL

const double STATUS_INTERVAL = 3.0

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

Definition at line 46 of file camera.h.

◆ TARGET_FRAME_LINK

const std::string TARGET_FRAME_LINK = "Workspace"

The name of the target frame in the NxLib.

Definition at line 67 of file camera.h.

◆ TF_REQUEST_TIMEOUT

const double TF_REQUEST_TIMEOUT = 10.

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

Definition at line 57 of file camera.h.

ERROR_CODE_TF
const int ERROR_CODE_TF
Definition: camera.h:72
ENSENSO_DEBUG
void ENSENSO_DEBUG(T... args)
Definition: logging.h:74
ERROR_CODE_UNKNOWN_EXCEPTION
const int ERROR_CODE_UNKNOWN_EXCEPTION
Definition: camera.h:71
tf2::TransformException


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46