Go to the documentation of this file.
15 node = NxLibItem()[
"rosParameterSets"][name];
16 node << defaultParameters;
53 if (cameraType != valMonocular)
72 std::string objectsFile =
"";
74 if (!objectsFile.empty())
82 std::string markerTopic;
83 double markerRate = 1;
91 nh, objectsFile, objectsFrame,
linkFrame, markerTopic, markerRate);
93 catch (std::exception
const& e)
95 ENSENSO_WARN(nh,
"Unable to load virtual objects file '%s'. Error: %s", objectsFile.c_str(), e.what());
112 statusPublisher = ensenso::ros::create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
nh,
"/diagnostics", 1);
131 if (jsonFile.empty())
137 if (file.is_open() && file.rdbuf())
139 std::stringstream buffer;
140 buffer << file.rdbuf();
141 std::string
const& jsonSettings = buffer.str();
143 NxLibItem tmpParameters = NxLibItem()[
"rosTemporaryParameters"];
146 tmpParameters.setJson(jsonSettings);
148 catch (NxLibException&)
150 ENSENSO_ERROR(
nh,
"The file '%s' does not contain valid JSON", jsonFile.c_str());
156 if (tmpParameters[itmParameters].
exists())
159 cameraNode[itmParameters] << tmpParameters[itmParameters];
164 cameraNode[itmParameters].setJson(jsonSettings,
true);
166 tmpParameters.erase();
168 NxLibCommand synchronize(cmdSynchronize,
params.
serial);
170 synchronize.execute();
173 if (saveAsDefaultParameters)
180 catch (NxLibException& e)
201 NxLibItem item(goal->path);
203 bool treeChanged =
false;
209 else if (goal->set_null)
214 else if (!goal->json_value.empty())
216 item.setJson(goal->json_value);
225 ensenso::action::AccessTreeResult result;
227 result.exists =
false;
230 result.exists =
true;
232 result.json_value = item.asJson();
238 catch (NxLibException&)
254 NxLibCommand
command(goal->command);
255 command.parameters().setJson(goal->parameters);
258 ensenso::action::ExecuteCommandResult result;
259 result.result =
command.result().asJson();
270 ensenso::action::GetParameterResult result;
275 for (
auto const& key : goal->keys)
306 diagnostic_msgs::msg::DiagnosticStatus cameraStatus;
307 cameraStatus.name =
"Camera";
309 cameraStatus.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
310 cameraStatus.message =
"OK";
314 cameraStatus.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
315 cameraStatus.message =
"Camera is no longer open";
318 diagnostic_msgs::msg::DiagnosticArray status;
320 status.status.push_back(cameraStatus);
328 info->width =
cameraNode[itmSensor][itmSize][0].asInt();
329 info->height =
cameraNode[itmSensor][itmSize][1].asInt();
341 info->binning_x =
cameraNode[itmParameters][itmCapture][itmBinning].asInt();
342 info->binning_y = info->binning_x;
372 if (targetFrame.empty())
388 geometry_msgs::msg::TransformStamped transformMsg;
402 NxLibItem()[itmLinks].setNull();
408 auto message = ensenso::std::make_shared<ensenso::msg::Parameter>();
419 switch (parameterMapping.
type)
422 message->bool_value = node.asBool();
425 message->float_value = node.asDouble();
428 message->string_value = node.asString();
434 ENSENSO_WARN(
nh,
"Reading the parameter %s, but the camera does not support it!", key.c_str());
456 ENSENSO_WARN(
nh,
"Writing the parameter %s, but the camera does not support it!", parameter.key.c_str());
460 switch (parameterMapping.
type)
463 node.set<
bool>(parameter.bool_value);
466 node.set<
double>(parameter.float_value);
469 node.set<std::string>(parameter.string_value);
495 NxLibCommand createCamera(cmdCreateCamera,
params.
serial);
496 createCamera.parameters()[itmSerialNumber] =
params.
serial;
498 createCamera.execute();
503 catch (NxLibException& e)
542 catch (NxLibException& e)
564 "Camera %s has an internal link (i.e. it is either extrinsically calibrated (workspace- or "
565 "hand-eye) or has a link to another camera), but camera and target frame are equal, which means "
566 "that neither a link nor a target frame has been provided. The images and 3d data retreived from "
567 "the camera are transformed by the NxLib with the transform stored in the camera's link node, "
568 "however, this transform is not known to tf. Please provide a link or target frame in order for "
569 "the transform to be published.",
592 catch (NxLibException&)
611 parameterSet.
node.erase();
633 bool changedParameters =
false;
637 changedParameters =
true;
640 if (changedParameters)
642 NxLibCommand synchronize(cmdSynchronize,
params.
serial);
644 synchronize.execute();
684 catch (NxLibException
const& e)
686 ENSENSO_WARN(
nh,
"Link does not exist. Therefore we cannot publish a transform to any target. Error message: %s",
687 e.getErrorText().c_str());
692 ENSENSO_WARN(
nh,
"Did not find a good transform from %s to %s. Transform has been set to identity",
#define GET_R_MATRIX(info)
void ENSENSO_WARN(T... args)
StampedTransformMsg fromTf(Transform const &transform, std::string parentFrame, std::string childFrame, ensenso::ros::Time timestamp)
void convert(const A &a, B &b)
CameraParameters(ensenso::ros::NodeHandle &nh, std::string const &cameraType, std::string serial)
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
void fillBasicCameraInfoFromNxLib(sensor_msgs::msg::CameraInfoPtr const &info) const
#define GET_P_MATRIX(info)
virtual void updateCameraTypeSpecifics()
void updateTransformations(tf2::Transform const &targetFrameTransformation) const
std::map< std::string, ParameterSet > parameterSets
NxLibItem node(NxLibItem const &cameraNode)
bool isValid(Transform const &transform)
const std::map< std::string, ParameterMapping > parameterInformation
std::unique_ptr< ExecuteCommandServer > executeCommandServer
bool meetsMinimumRequirement(int majorRequired, int minorRequired) const
#define START_NXLIB_ACTION(ACTION_NAME, ACTION_SERVER)
ROSLIB_DECL std::string command(const std::string &cmd)
std::string getNxLibTargetFrameName() const
ParameterSet(std::string const &name, NxLibItem const &defaultParameters)
void ENSENSO_INFO(T... args)
Transform transformFromNxLib(NxLibItem const &node)
const std::string DEFAULT_PARAMETER_SET
#define FINISH_NXLIB_ACTION(ACTION_NAME)
void writeTransformToNxLib(Transform const &transform, NxLibItem const &node)
const double TF_REQUEST_TIMEOUT
std::unique_ptr< ensenso_camera::VirtualObjectHandler > virtualObjectHandler
void saveDefaultParameterSet()
bool cameraIsOpen() const
void onGetParameter(ensenso::action::GetParameterGoalConstPtr const &goal)
void onAccessTree(ensenso::action::AccessTreeGoalConstPtr const &goal)
void loadParameterSet(std::string name)
virtual void writeParameter(ensenso::msg::Parameter const ¶meter)
#define CREATE_TIMER(nh, duration_in_seconds, callback_ref, object_ptr)
void saveParameterSet(std::string name)
void ENSENSO_DEBUG(T... args)
std::unique_ptr< tf2_ros::TransformBroadcaster > make_tf2_broadcaster(ensenso::ros::NodeHandle const &nh)
ensenso::ros::Timer cameraPosePublisher
def message(msg, *args, **kwargs)
virtual void startServers() const
std::string fileCameraPath
std::string currentParameterSet
std::unique_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
geometry_msgs::msg::TransformStamped stampedLinkToCamera()
#define MAKE_SERVER(CallbackClass, ActionName, TopicName)
#define GET_D_MATRIX(info)
ensenso::ros::Timer statusTimer
bool get_parameter(NodeHandle &nh, const char *name, T ¶meter)
bool cameraIsAvailable() const
#define LOG_NXLIB_EXCEPTION(EXCEPTION)
void publishStatus(TIMER_CALLBACK_DECLARATION_ARGS)
bool loadSettings(std::string const &jsonFile, bool saveAsDefaultParameters=false)
ensenso::ros::Publisher< diagnostic_msgs::msg::DiagnosticArray > statusPublisher
::ros::NodeHandle NodeHandle
virtual void updateCameraInfo()=0
std::unique_ptr< tf2_ros::TransformListener > transformListener
virtual void initStatusTimer()
virtual void initTfPublishTimer()
NxLibVersion nxLibVersion
std::string toString() const
bool isIdentity(Transform const &transform)
std::string expandPath(std::string const &path_)
std::map< std::string, geometry_msgs::msg::TransformStamped > transformationCache
inline ::ros::Time now(ensenso::ros::NodeHandle const &nh)
void onExecuteCommand(ensenso::action::ExecuteCommandGoalConstPtr const &goal)
std::unique_ptr< tf2_ros::Buffer > make_tf2_buffer(ensenso::ros::NodeHandle const &nh)
virtual ensenso::msg::ParameterPtr readParameter(std::string const &key) const
bool parameterExists(std::string const &key)
const std::string TARGET_FRAME_LINK
const double POSE_TF_INTERVAL
NxLibItem defaultParameters
std::unique_ptr< AccessTreeServer > accessTreeServer
std::unique_ptr< GetParameterServer > getParameterServer
ImagePtr imageFromNxLibNode(NxLibItem const &node, std::string const &frame, bool isFileCamera)
#define GET_K_MATRIX(info)
void ENSENSO_WARN_ONCE(T... args)
void ENSENSO_ERROR(T... args)
Camera(ensenso::ros::NodeHandle &nh, CameraParameters params)
const std::string PLUMB_BOB
std::unique_ptr< SetParameterServer > setParameterServer
#define TIMER_CALLBACK_DEFINITION_ARGS
inline ::ros::Duration durationFromSeconds(double d)
std::unique_ptr< tf2_ros::Buffer > tfBuffer
ensenso::ros::NodeHandle nh
tf2::Transform getCameraToLinkTransform()
void updateGlobalLink(ensenso::ros::Time time, std::string targetFrame="", bool useCachedTransformation=false) const
const double STATUS_INTERVAL
void publishCurrentLinks(TIMER_CALLBACK_DECLARATION_ARGS)
void move(std::vector< T > &a, std::vector< T > &b)
ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46