tf2_ros::Buffer causes linking error
Hi, I wanted to use tfListener in my .cpp file but when i declare an object of tf2_ros::Buffer class ide gives a linking error; however, if I comment that line out error dissappears. I'm sending code and error. My rosdistro: melodic, OS: Ubuntu 18.04.4 LTS gcc: gcc (Ubuntu 7.4.0-1ubuntu1~18.04.1) 7.4.0 Linux distro: Linux version 4.15.0-88-generic (buildd@lgw01-amd64-036) (gcc version 7.4.0 (Ubuntu 7.4.0-1ubuntu1~18.04.1)) #88-Ubuntu SMP Tue Feb 11 20:11:34 UTC 2020 Kernel: 4.15.0-88-generic Ide:Clion
assignment2.cpp:
include "ros/ros.h"
include "std_msgs/Float32.h"
include "geometry_msgs/PoseStamped.h"
include "geometry_msgs/PoseArray.h"
include "sensor_msgs/PointCloud2.h"
include "std_msgs/String.h"
include "std_msgs/Float32.h"
include "kdl/chain.hpp"
include "kdl/chainfksolver.hpp"
include "kdl/chainfksolverpos_recursive.hpp"
include "kdl/chainiksolverpos_lma.hpp"
include "kdl/chainiksolvervelpinvgivens.hpp"
include "kdl/chainiksolverposnrjl.hpp"
include "kdl/frames_io.hpp"
include "tf2ros/transformlistener.h"
include "tf2sensormsgs/tf2sensormsgs.h"
include "tf2geometrymsgs/tf2geometrymsgs.h"
include "tf2ros/messagefilter.h"
include "message_filters/subscriber.h"
include "tf2_ros/buffer.h"
include "tf2ros/bufferclient.h"
include "tf2ros/bufferinterface.h"
include "tf2ros/bufferserver.h"
include "tf2ros/messagefilter.h"
include "tf2ros/statictransform_broadcaster.h"
include "tf2ros/transformbroadcaster.h"
include
include
define UR10_DOF 6
geometry_msgs::Pose calculatedPosition;
void func1(const sensormsgs::PointCloud2& pointCloud) { ros::NodeHandle nodeHandle; tf2ros::Buffer tfBuffer; //tf2_ros::TransformListener tfListener(tfBuffer);
/*ros::Rate rate(10.0);
while (nodeHandle.ok()) {
sensor_msgs::PointCloud2 transformStamped;
try {
tfBuffer.lookupTransform("UR10_base",
"kinect_depth", ros::Time(0));
} catch (tf2::TransformException &exception) {
ROS_WARN("%s", exception.what());
ros::Duration(1.0).sleep();
continue;
}
rate.sleep();
}*/
}
void func2(const std_msgs::String& string) {
}
void func3(const std_msgs::Float32& float1) {
}
void func4(const std_msgs::Float32& float2) {
}
void endEffectorPositionCallback(const geometry_msgs::PoseStampedConstPtr& endEffectorPositionMessage) { std::cout << "End Effector Position :" << "[ "<< endEffectorPositionMessage->pose.position.x << " , " << endEffectorPositionMessage->pose.position.y << " , " << endEffectorPositionMessage->pose.position.z << " ]" << std::endl; }
KDL::Chain initChainUR10() { KDL::Chain chain;
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,-KDL::PI/2,0), KDL::Vector( -0.09265011549, 0, 0.0833499655128 ))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,0,0), KDL::Vector( 0.612088978291, 0, 0.0196119993925 ))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,0,0), KDL::Vector( 0.572199583054, 0, -0.00660470128059 ))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,KDL::PI/2,0), KDL::Vector( 0.0572912693024, 0,0.0584142804146 ))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,-KDL::PI/2,0), KDL::Vector( -0.0573025941849, 0,0.0583996772766))));
chain.addSegment(KDL::Segment(KDL::Joint(KDL::Joint::RotZ),KDL::Frame(KDL::Rotation::RPY(0,0,0), KDL::Vector( 0, 0, 0.110513627529 ))));
return chain;
}
int main(int argc, char **argv) { //ROSINFOSTREAM("321"); ros::init(argc,argv,"UR10_Main");
ros::NodeHandle node;
ros::Subscriber subscriber1 =node.subscribe("/kinect/depth",10,func1);
ros::Subscriber subscriber2 =node.subscribe("/Cube_Target_Basket",10,func2);
ros::Subscriber subscriber3 =node.subscribe("/Accumulated_Points",10,func3);
ros::Subscriber subscriber4 =node.subscribe("/Total_Points",10,func4);
ros::Publisher joints[6];
joints[0] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint001",1000);
joints[1] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint002",1000);
joints[2] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint003",1000);
joints[3] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint004",1000);
joints[4] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint005",1000);
joints[5] = node.advertise<std_msgs::Float32>("/UR10/jointAngles/joint006",1000);
for(int index=0;index<UR10_DOF;index++){
std_msgs::Float32 jointMessage;
jointMessage.data = 0;
joints[index].publish(jointMessage);
}
ros::Rate loop(10);
ros::Subscriber endEffectorPositionSubscriber = node.subscribe<geometry_msgs::PoseStamped>("/UR10/positions/endEffectorPosition",1000,endEffectorPositionCallback);
KDL::Chain chain = initChainUR10();
unsigned int nj = chain.getNrOfJoints();
while(ros::ok()) {
KDL::ChainFkSolverPos_recursive fksolver = KDL::ChainFkSolverPos_recursive(chain);
unsigned int nj = chain.getNrOfJoints();
KDL::JntArray jointpositions = KDL::JntArray(nj);
for(unsigned int i=0;i<6;i++){
jointpositions(i)=(double)10 * KDL::PI/180; // You can assign angles to go like this.
}
for(unsigned int i=0;i<6;i++){ // Sending joint angles to robot.
std_msgs::Float32 jointMessage;
jointMessage.data = 10*KDL::PI/180;
joints[i].publish(jointMessage);
}
// Create the frame that will contain the results
KDL::Frame cartpos;
// Calculate forward position kinematics
bool kinematics_status;
kinematics_status = fksolver.JntToCart(jointpositions,cartpos);
if(kinematics_status>=0){
calculatedPosition.position.x=(double)cartpos.p.x();
calculatedPosition.position.y=(double)cartpos.p.y();
calculatedPosition.position.z=(double)cartpos.p.z();
}
// You can now follow end effector position and real position in terminal
/*
You can check KDL::ChainIkSolverPos_LMA for inverse kinematic solver.
You can use this matrix for ChainIkSolverPos_LMA if you'll use that.
Eigen::Matrix<double,6,1> L;
L(0)=1;L(1)=1;L(2)=1;
L(3)=0.01;L(4)=0.01;L(5)=0.01;
goalEndEffectorPosition = KDL::Frame(
KDL::Rotation::RPY(0,0,0),
KDL::Vector(0,0,0)
);
*/
ros::spinOnce();
loop.sleep();
}
return 0;
}
error:
====================[ Build | assignment2 | Debug ]=============================
/snap/clion/103/bin/cmake/linux/bin/cmake --build /home/musa/catkinws/src/colorsassignments/assignment2/cmake-build-debug --target assignment2 -- -j 2
[ 0%] Built target rosgraphmsgsgeneratemessagesnodejs
[ 0%] Built target geometrymsgsgeneratemessagespy
[ 0%] Built target geometrymsgsgeneratemessageslisp
[ 0%] Built target geometrymsgsgeneratemessagescpp
[ 0%] Built target stdmsgsgeneratemessagesnodejs
[ 0%] Built target stdmsgsgeneratemessageslisp
[ 0%] Built target stdmsgsgeneratemessagescpp
[ 0%] Built target roscppgeneratemessagescpp
[ 0%] Built target geometrymsgsgeneratemessagesnodejs
[ 0%] Built target roscppgeneratemessageslisp
[ 0%] Built target roscppgeneratemessageseus
[ 0%] Built target stdmsgsgeneratemessagespy
[ 0%] Built target roscppgeneratemessagesnodejs
[ 0%] Built target geometrymsgsgeneratemessageseus
[ 0%] Built target roscppgeneratemessagespy
[ 0%] Built target rosgraphmsgsgeneratemessagescpp
[ 0%] Built target rosgraphmsgsgeneratemessageseus
[ 0%] Built target stdmsgsgeneratemessageseus
[ 0%] Built target rosgraphmsgsgeneratemessageslisp
[ 0%] Built target rosgraphmsgsgeneratemessagespy
Scanning dependencies of target assignment2
[ 50%] Building CXX object CMakeFiles/assignment2.dir/src/assignment2.cpp.o
[100%] Linking CXX executable devel/lib/assignment2/assignment2
CMakeFiles/assignment2.dir/src/assignment2.cpp.o: In function `func1(sensormsgs::PointCloud2std::allocator<void > const&)':
/home/musa/catkinws/src/colorsassignments/assignment2/src/assignment2.cpp:43: undefined reference to `tf2ros::Buffer::Buffer(ros::Duration, bool)'
CMakeFiles/assignment2.dir/src/assignment2.cpp.o: In function tf2_ros::Buffer::~Buffer()':
/opt/ros/melodic/include/tf2_ros/buffer.h:51: undefined reference to
vtable for tf2ros::Buffer'
/opt/ros/melodic/include/tf2ros/buffer.h:51: undefined reference to vtable for tf2_ros::Buffer'
/opt/ros/melodic/include/tf2_ros/buffer.h:51: undefined reference to
tf2::BufferCore::~BufferCore()'
collect2: error: ld returned 1 exit status
CMakeFiles/assignment2.dir/build.make:108: recipe for target 'devel/lib/assignment2/assignment2' failed
make[3]: *** [devel/lib/assignment2/assignment2] Error 1
CMakeFiles/Makefile2:121: recipe for target 'CMakeFiles/assignment2.dir/all' failed
make[2]: *** [CMakeFiles/assignment2.dir/all] Error 2
CMakeFiles/Makefile2:128: recipe for target 'CMakeFiles/assignment2.dir/rule' failed
make[1]: *** [CMakeFiles/assignment2.dir/rule] Error 2
Makefile:175: recipe for target 'assignment2' failed
make: *** [assignment2] Error 2
buffer.h (if needed)
/* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */
/** \author Wim Meeussen */
ifndef TF2ROSBUFFER_H
define TF2ROSBUFFER_H
include
include
include
include
include
namespace tf2_ros {
/** \brief Standard implementation of the tf2ros::BufferInterface abstract data type. * * Inherits tf2ros::BufferInterface and tf2::BufferCore. * Stores known frames and offers a ROS service, "tfframes", which responds to client requests * with a response containing a tf2msgs::FrameGraph representing the relationship of known frames. */ class Buffer: public BufferInterface, public tf2::BufferCore { public: using tf2::BufferCore::lookupTransform; using tf2::BufferCore::canTransform;
/**
* @brief Constructor for a Buffer object
* @param cache_time How long to keep a history of transforms
* @param debug Whether to advertise the view_frames service that exposes debugging information from the buffer
* @return
*/
Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false);
/** \brief Get the transform between two frames by frame ID.
* \param target_frame The frame to which data should be transformed
* \param source_frame The frame where the data originated
* \param time The time at which the value of the transform is desired. (0 will get the latest)
* \param timeout How long to block before failing
* \return The transform between the frames
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
virtual geometry_msgs::TransformStamped
lookupTransform(const std::string& target_frame, const std::string& source_frame,
const ros::Time& time, const ros::Duration timeout) const;
/** \brief Get the transform between two frames by frame ID assuming fixed frame.
* \param target_frame The frame to which data should be transformed
* \param target_time The time to which the data should be transformed. (0 will get the latest)
* \param source_frame The frame where the data originated
* \param source_time The time at which the source_frame should be evaluated. (0 will get the latest)
* \param fixed_frame The frame in which to assume the transform is constant in time.
* \param timeout How long to block before failing
* \return The transform between the frames
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
virtual geometry_msgs::TransformStamped
lookupTransform(const std::string& target_frame, const ros::Time& target_time,
const std::string& source_frame, const ros::Time& source_time,
const std::string& fixed_frame, const ros::Duration timeout) const;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
* \param source_frame The frame from which to transform
* \param target_time The time at which to transform
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL
* \return True if the transform is possible, false otherwise
*/
virtual bool
canTransform(const std::string& target_frame, const std::string& source_frame,
const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
* \param target_time The time into which to transform
* \param source_frame The frame from which to transform
* \param source_time The time from which to transform
* \param fixed_frame The frame in which to treat the transform as constant in time
* \param timeout How long to block before failing
* \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL
* \return True if the transform is possible, false otherwise
*/
virtual bool
canTransform(const std::string& target_frame, const ros::Time& target_time,
const std::string& source_frame, const ros::Time& source_time,
const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const;
private: bool getFrames(tf2msgs::FrameGraph::Request& req, tf2msgs::FrameGraph::Response& res) ;
// conditionally error if dedicated_thread unset.
bool checkAndErrorDedicatedThreadPresent(std::string* errstr) const;
ros::ServiceServer frames_server_;
}; // class
static const std::string threading_error = "Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.";
} // namespace
endif // TF2ROSBUFFER_H
buffer_core.h (if needed)
/* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */
/** \author Tully Foote */
ifndef TF2BUFFERCORE_H
define TF2BUFFERCORE_H
include "transform_storage.h"
include
include
include "ros/duration.h"
include "ros/time.h"
//#include "geometry_msgs/TwistStamped.h"
include "geometry_msgs/TransformStamped.h"
//////////////////////////backwards startup for porting //#include "tf/tf.h"
include
include
include
include
namespace tf2 {
typedef std::pair
class TimeCacheInterface;
typedef boost::shared_ptr
enum TransformableResult { TransformAvailable, TransformFailure, };
/** \brief A Class which provides coordinate transforms between any two frames in a system. * * This class provides a simple interface to allow recording and lookup of * relationships between arbitrary frames of the system. * * libTF assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames. * For example your typical robot would have a transform from global to real world. And then from base to hand, and from base to head. * But Base to Hand really is composed of base to shoulder to elbow to wrist to hand. * libTF is designed to take care of all the intermediate steps for you. * * Internal Representation * libTF will store frames with the parameters necessary for generating the transform into that frame from it's parent and a reference to the parent frame. * Frames are designated using an std::string * 0 is a frame without a parent (the top of a tree) * The positions of frames over time must be pushed in. * * All function calls which pass frame ids can potentially throw the exception tf::LookupException / class BufferCore { public: /************ Constants ***********************/ static const int DEFAULTCACHETIME = 10; //!< The default amount of time to cache data in seconds static const uint32t MAXGRAPH_DEPTH = 1000UL; //!< Maximum graph search depth (deeper graphs will be assumed to have loops)
/** Constructor * \param interpolating Whether to interpolate, if this is false the closest value will be returned * \param cachetime How long to keep a history of transforms in nanoseconds * */ BufferCore(ros::Duration cachetime_ = ros::Duration(DEFAULTCACHETIME)); virtual ~BufferCore(void);
/** \brief Clear all data */ void clear();
/** \brief Add transform information to the tf data structure * \param transform The transform to store * \param authority The source of the information for this transform * \param isstatic Record this transform as a static transform. It will be good across all time. (This cannot be changed after the first call.) * \return True unless an error occured */ bool setTransform(const geometrymsgs::TransformStamped& transform, const std::string & authority, bool is_static = false);
/*********** Accessors *************/
/** \brief Get the transform between two frames by frame ID. * \param targetframe The frame to which data should be transformed * \param sourceframe The frame where the data originated * \param time The time at which the value of the transform is desired. (0 will get the latest) * \return The transform between the frames * * Possible exceptions tf2::LookupException, tf2::ConnectivityException, * tf2::ExtrapolationException, tf2::InvalidArgumentException */ geometrymsgs::TransformStamped lookupTransform(const std::string& targetframe, const std::string& source_frame, const ros::Time& time) const;
/** \brief Get the transform between two frames by frame ID assuming fixed frame. * \param targetframe The frame to which data should be transformed * \param targettime The time to which the data should be transformed. (0 will get the latest) * \param sourceframe The frame where the data originated * \param sourcetime The time at which the sourceframe should be evaluated. (0 will get the latest) * \param fixedframe The frame in which to assume the transform is constant in time. * \return The transform between the frames * * Possible exceptions tf2::LookupException, tf2::ConnectivityException, * tf2::ExtrapolationException, tf2::InvalidArgumentException */
geometrymsgs::TransformStamped lookupTransform(const std::string& targetframe, const ros::Time& targettime, const std::string& sourceframe, const ros::Time& sourcetime, const std::string& fixedframe) const;
/* \brief Lookup the twist of the trackingframe with respect to the observation frame in the referenceframe using the reference point
* \param trackingframe The frame to track
* \param observationframe The frame from which to measure the twist
* \param referenceframe The reference frame in which to express the twist
* \param referencepoint The reference point with which to express the twist
* \param referencepointframe The frameid in which the reference point is expressed
* \param time The time at which to get the velocity
* \param duration The period over which to average
* \return twist The twist output
*
* This will compute the average velocity on the interval
* (time - duration/2, time+duration/2). If that is too close to the most
* recent reading, in which case it will shift the interval up to
* duration/2 to prevent extrapolation.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*
* New in geometry 1.1
/
/
geometrymsgs::Twist
lookupTwist(const std::string& trackingframe, const std::string& observationframe, const std::string& referenceframe,
const tf::Point & referencepoint, const std::string& referencepointframe,
const ros::Time& time, const ros::Duration& averaginginterval) const;
/
/ \brief lookup the twist of the tracking frame with respect to the observational frame
*
* This is a simplified version of
* lookupTwist with it assumed that the reference point is the
* origin of the tracking frame, and the reference frame is the
* observation frame.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*
* New in geometry 1.1
/
/
geometrymsgs::Twist
lookupTwist(const std::string& trackingframe, const std::string& observationframe,
const ros::Time& time, const ros::Duration& averaginginterval) const;
/
/* \brief Test if a transform is possible
* \param targetframe The frame into which to transform
* \param sourceframe The frame from which to transform
* \param time The time at which to transform
* \param errormsg A pointer to a string which will be filled with why the transform failed, if not NULL
* \return True if the transform is possible, false otherwise
/
bool canTransform(const std::string& targetframe, const std::string& sourceframe,
const ros::Time& time, std::string error_msg = NULL) const;
/** \brief Test if a transform is possible * \param targetframe The frame into which to transform * \param targettime The time into which to transform * \param sourceframe The frame from which to transform * \param sourcetime The time from which to transform * \param fixedframe The frame in which to treat the transform as constant in time * \param errormsg A pointer to a string which will be filled with why the transform failed, if not NULL * \return True if the transform is possible, false otherwise / bool canTransform(const std::string& targetframe, const ros::Time& targettime, const std::string& sourceframe, const ros::Time& sourcetime, const std::string& fixed_frame, std::string error_msg = NULL) const;
/** \brief A way to see what frames have been cached in yaml format * Useful for debugging tools */ std::string allFramesAsYAML(double current_time) const;
/** Backwards compatibility for #84 */ std::string allFramesAsYAML() const;
/** \brief A way to see what frames have been cached * Useful for debugging */ std::string allFramesAsString() const;
typedef boost::function
/// \brief Internal use only TransformableCallbackHandle addTransformableCallback(const TransformableCallback& cb); /// \brief Internal use only void removeTransformableCallback(TransformableCallbackHandle handle); /// \brief Internal use only TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string& targetframe, const std::string& sourceframe, ros::Time time); /// \brief Internal use only void cancelTransformableRequest(TransformableRequestHandle handle);
// Tell the buffer that there are multiple threads serviciing it. // This is useful for derived classes to know if they can block or not. void setUsingDedicatedThread(bool value) { usingdedicatedthread_ = value;}; // Get the state of usingdedicatedthread_ bool isUsingDedicatedThread() const { return usingdedicatedthread_;};
/* Backwards compatability section for tf::Transformer you should not use these */
/**
* \brief Add a callback that happens when a new transform has arrived
*
* \param callback The callback, of the form void func();
* \return A boost::signals2::connection object that can be used to remove this
* listener
*/
boost::signals2::connection _addTransformsChangedListener(boost::function
/**@brief Check if a frame exists in the tree * @param frameidstr The frame id in question */ bool frameExists(const std::string& frameid_str) const;
/**@brief Fill the parent of a frame. * @param frameid The frame id of the frame in question * @param parent The reference to the string to fill the parent * Returns true unless "NOPARENT" */ bool getParent(const std::string& frameid, ros::Time time, std::string& parent) const;
/** \brief A way to get a std::vector of available frame ids */ void _getFrameStrings(std::vectorstd::string& ids) const;
CompactFrameID lookupFrameNumber(const std::string& frameidstr) const { return lookupFrameNumber(frameidstr); } CompactFrameID _lookupOrInsertFrameNumber(const std::string& frameidstr) { return lookupOrInsertFrameNumber(frameid_str); }
int getLatestCommonTime(CompactFrameID targetframe, CompactFrameID sourceframe, ros::Time& time, std::string* errorstring) const { boost::mutex::scopedlock lock(framemutex); return getLatestCommonTime(targetframe, sourceframe, time, errorstring); }
CompactFrameID validateFrameId(const char* functionnamearg, const std::string& frameid) const { return validateFrameId(functionnamearg, frame_id); }
/**@brief Get the duration over which this transformer will cache */ ros::Duration getCacheLength() { return cachetime;}
/** \brief Backwards compatabilityA way to see what frames have been cached * Useful for debugging */ std::string allFramesAsDot(double currenttime) const; std::string _allFramesAsDot() const;
/** \brief Backwards compatabilityA way to see what frames are in a chain * Useful for debugging */ void chainAsVector(const std::string & targetframe, ros::Time targettime, const std::string & sourceframe, ros::Time sourcetime, const std::string & fixedframe, std::vectorstd::string& output) const;
private:
/** \brief A way to see what frames have been cached * Useful for debugging. Use this call internally. */ std::string allFramesAsStringNoLock() const;
/******************** Internal Storage ****************/
/** \brief The pointers to potential frames that the tree can be made of.
* The frames will be dynamically allocated at run time when set the first time. */
typedef std::vector
/** \brief A mutex to protect testing and allocating new frames on the above vector. */ mutable boost::mutex framemutex;
/** \brief A map from string frame ids to CompactFrameID /
typedef boost::unorderedmap
/// How long to cache transform history ros::Duration cachetime;
typedef boost::unorderedmap
struct TransformableRequest
{
ros::Time time;
TransformableRequestHandle requesthandle;
TransformableCallbackHandle cbhandle;
CompactFrameID targetid;
CompactFrameID sourceid;
std::string targetstring;
std::string sourcestring;
};
typedef std::vector
struct RemoveRequestByCallback; struct RemoveRequestByID;
// Backwards compatability for tf messagefilter
typedef boost::signals2::signal
/************************* Internal Functions ****************************/
/** \brief An accessor to get a frame, which will throw an exception if the frame is no there. * \param framenumber The frameID of the desired Reference Frame * * This is an internal function which will get the pointer to the frame associated with the frame id * Possible Exception: tf::LookupException */ TimeCacheInterfacePtr getFrame(CompactFrameID cframe_id) const;
TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
bool warnFrameId(const char* functionnamearg, const std::string& frameid) const; CompactFrameID validateFrameId(const char* functionnamearg, const std::string& frameid) const;
/// String to number for frame lookup with dynamic allocation of new frames CompactFrameID lookupFrameNumber(const std::string& frameid_str) const;
/// String to number for frame lookup with dynamic allocation of new frames CompactFrameID lookupOrInsertFrameNumber(const std::string& frameid_str);
///Number to string frame lookup may throw LookupException if number invalid const std::string& lookupFrameString(CompactFrameID frameidnum) const;
void createConnectivityErrorString(CompactFrameID sourceframe, CompactFrameID targetframe, std::string* out) const;
/*@brief Return the latest rostime which is common across the spanning set * zero if fails to cross */ int getLatestCommonTime(CompactFrameID targetframe, CompactFrameID sourceframe, ros::Time& time, std::string error_string) const;
template
/*@brief Traverse the transform tree. If framechain is not NULL, store the traversed frame tree in vector framechain.
* */
template
void testTransformableRequests(); bool canTransformInternal(CompactFrameID targetid, CompactFrameID sourceid, const ros::Time& time, std::string* errormsg) const; bool canTransformNoLock(CompactFrameID targetid, CompactFrameID sourceid, const ros::Time& time, std::string* errormsg) const;
//Whether it is safe to use canTransform with a timeout. (If another thread is not provided it will always timeout.) bool usingdedicatedthread_;
public: friend class TestBufferCore; // For unit testing
};
/** A helper class for testing internal APIs /
class TestBufferCore
{
public:
int walkToTopParent(BufferCore& buffer, ros::Time time, CompactFrameID targetid, CompactFrameID source_id, std::string errorstring, std::vector
endif //TF2COREH
Thanks.
Asked by musa.ihtiyar on 2020-03-02 01:17:41 UTC
Comments