Added a ros parameter to enable/disable if a transform is broadcasted everytime and anchor is found
This commit is contained in:
Родитель
f5e0f87445
Коммит
76e37855ff
|
@ -118,6 +118,9 @@ class AsaRosNode {
|
|||
std::string camera_frame_id_;
|
||||
std::string anchor_frame_id_;
|
||||
|
||||
// A flag indicating if the node will send the anchor transforms to the tf tree. Default is true.
|
||||
bool broadcast_anchor_tf_;
|
||||
|
||||
// Timeout to wait for TF messages, in seconds. 0.0 = instantaneous. 1.0 =
|
||||
// will wait a full second on any failed attempt.
|
||||
double tf_lookup_timeout_;
|
||||
|
|
|
@ -29,6 +29,8 @@
|
|||
<param name="camera_frame_id" value="camera_fisheye1_optical_frame" />
|
||||
<!-- Timeout to wait for TF lookups to finish. If you get a lot of TF errors but still smome valid lookups, try increasing this. -->
|
||||
<param name="tf_lookup_timeout" value="0.1" />
|
||||
<!-- A flag indicating if the node will send the anchor transforms to the tf tree when an anchor is found. Default is true. -->
|
||||
<param name="broadcast_anchor_tf" value="true" />
|
||||
|
||||
<param name="account_id" value="$(arg account_id)"/>
|
||||
<param name="account_key" value="$(arg account_key)"/>
|
||||
|
|
|
@ -22,6 +22,7 @@ AsaRosNode::AsaRosNode(const ros::NodeHandle& nh,
|
|||
world_frame_id_("world"),
|
||||
camera_frame_id_(""),
|
||||
anchor_frame_id_(""),
|
||||
broadcast_anchor_tf_(true),
|
||||
tf_lookup_timeout_(0.1),
|
||||
prev_frame_timestamp_() {
|
||||
initFromRosParams();
|
||||
|
@ -102,6 +103,7 @@ void AsaRosNode::initFromRosParams() {
|
|||
nh_private_.param("world_frame_id", world_frame_id_, world_frame_id_);
|
||||
nh_private_.param("camera_frame_id", camera_frame_id_, camera_frame_id_);
|
||||
nh_private_.param("anchor_frame_id", anchor_frame_id_, anchor_frame_id_);
|
||||
nh_private_.param("broadcast_anchor_tf", broadcast_anchor_tf_, broadcast_anchor_tf_);
|
||||
nh_private_.param("tf_lookup_timeout", tf_lookup_timeout_,
|
||||
tf_lookup_timeout_);
|
||||
|
||||
|
@ -214,7 +216,9 @@ void AsaRosNode::anchorFoundCallback(
|
|||
T_W_A_msg.child_frame_id = anchor_id;
|
||||
}
|
||||
|
||||
tf_broadcaster_.sendTransform(T_W_A_msg);
|
||||
if (broadcast_anchor_tf_) {
|
||||
tf_broadcaster_.sendTransform(T_W_A_msg);
|
||||
}
|
||||
|
||||
// Also publish this as a topic.
|
||||
asa_ros_msgs::FoundAnchor anchor_msg;
|
||||
|
|
Загрузка…
Ссылка в новой задаче