Go to the documentation of this file. 1 #ifndef AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
2 #define AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
6 #include <dart/dart.hpp>
7 #include <tf/transform_listener.h>
16 namespace perception {
46 ros::NodeHandle nodeHandle,
47 const std::string& markerTopic,
48 std::shared_ptr<AssetDatabase> assetData,
49 std::shared_ptr<aikido::io::CatkinResourceRetriever> resourceRetriever,
50 const std::string& referenceFrameId,
51 dart::dynamics::Frame* referenceLink);
63 ros::Duration timeout = ros::Duration(),
64 ros::Time timestamp = ros::Time(0.0),
65 std::vector<DetectedObject>* detectedObjects =
nullptr)
override;
93 #endif // AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
The interface for the generic perception module.
Definition: PerceptionModule.hpp:16
tf::TransformListener mTfListener
Listens to the transform attached to the node.
Definition: PoseEstimatorModule.hpp:87
bool detectObjects(const aikido::planner::WorldPtr &env, ros::Duration timeout=ros::Duration(), ros::Time timestamp=ros::Time(0.0), std::vector< DetectedObject > *detectedObjects=nullptr) override
Run the specific detector via a service call or ROS message reception, lookup the transform between t...
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
ros::NodeHandle mNodeHandle
For the ROS node that will work with the April Tags module.
Definition: PoseEstimatorModule.hpp:69
std::string mReferenceFrameId
The desired reference frame for the object pose.
Definition: PoseEstimatorModule.hpp:81
std::string mMarkerTopic
The name of the ROS topic to read marker info from.
Definition: PoseEstimatorModule.hpp:72
std::shared_ptr< aikido::io::CatkinResourceRetriever > mResourceRetriever
To retrieve resources from disk and from packages.
Definition: PoseEstimatorModule.hpp:78
std::shared_ptr< World > WorldPtr
Definition: World.hpp:14
PoseEstimatorModule(ros::NodeHandle nodeHandle, const std::string &markerTopic, std::shared_ptr< AssetDatabase > assetData, std::shared_ptr< aikido::io::CatkinResourceRetriever > resourceRetriever, const std::string &referenceFrameId, dart::dynamics::Frame *referenceLink)
Construct a PoseEstimator receiver that subscribes to the specified topic where objects' pose informa...
virtual ~PoseEstimatorModule()=default
Instantiates the PerceptionModule specifically for PoseEstimator.
Definition: PoseEstimatorModule.hpp:26
std::shared_ptr< AssetDatabase > mAssetData
The pointer to the loader of visual asset data.
Definition: PoseEstimatorModule.hpp:75
dart::dynamics::Frame * mReferenceLink
The reference frame of HERB to transform with respect to.
Definition: PoseEstimatorModule.hpp:84