Aikido
PoseEstimatorModule.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
2 #define AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
3 
4 #include <string>
5 
6 #include <dart/dart.hpp>
7 #include <tf/transform_listener.h>
8 
10 #include "aikido/io/util.hpp"
11 #include "aikido/io/yaml.hpp"
15 
16 namespace aikido {
17 namespace perception {
18 
28 {
29 public:
47  ros::NodeHandle nodeHandle,
48  const std::string& markerTopic,
49  std::shared_ptr<AssetDatabase> assetData,
50  std::shared_ptr<aikido::io::CatkinResourceRetriever> resourceRetriever,
51  const std::string& referenceFrameId,
52  dart::dynamics::Frame* referenceLink);
53 
54  virtual ~PoseEstimatorModule() = default;
55 
62  bool detectObjects(
63  const aikido::planner::WorldPtr& env,
64  ros::Duration timeout = ros::Duration(),
65  ros::Time timestamp = ros::Time(0.0),
66  std::vector<DetectedObject>* detectedObjects = nullptr) override;
67 
68 private:
70  ros::NodeHandle mNodeHandle;
71 
73  std::string mMarkerTopic;
74 
76  std::shared_ptr<AssetDatabase> mAssetData;
77 
79  std::shared_ptr<aikido::io::CatkinResourceRetriever> mResourceRetriever;
80 
82  std::string mReferenceFrameId;
83 
85  dart::dynamics::Frame* mReferenceLink;
86 
88  tf::TransformListener mTfListener;
89 };
90 
91 } // namespace perception
92 } // namespace aikido
93 
94 #endif // AIKIDO_PERCEPTION_POSEESTIMATORMODULE_HPP_
aikido::perception::PerceptionModule
The interface for the generic perception module.
Definition: PerceptionModule.hpp:16
aikido::perception::PoseEstimatorModule::mTfListener
tf::TransformListener mTfListener
Listens to the transform attached to the node.
Definition: PoseEstimatorModule.hpp:88
aikido::perception::PoseEstimatorModule::detectObjects
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...
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::perception::PoseEstimatorModule::mNodeHandle
ros::NodeHandle mNodeHandle
For the ROS node that will work with the April Tags module.
Definition: PoseEstimatorModule.hpp:70
aikido::perception::PoseEstimatorModule::mReferenceFrameId
std::string mReferenceFrameId
The desired reference frame for the object pose.
Definition: PoseEstimatorModule.hpp:82
aikido::perception::PoseEstimatorModule::mMarkerTopic
std::string mMarkerTopic
The name of the ROS topic to read marker info from.
Definition: PoseEstimatorModule.hpp:73
util.hpp
aikido::perception::PoseEstimatorModule::mResourceRetriever
std::shared_ptr< aikido::io::CatkinResourceRetriever > mResourceRetriever
To retrieve resources from disk and from packages.
Definition: PoseEstimatorModule.hpp:79
aikido::planner::WorldPtr
std::shared_ptr< World > WorldPtr
Definition: World.hpp:14
yaml.hpp
aikido::perception::PoseEstimatorModule::PoseEstimatorModule
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...
aikido::perception::PoseEstimatorModule::~PoseEstimatorModule
virtual ~PoseEstimatorModule()=default
aikido::perception::PoseEstimatorModule
Instantiates the PerceptionModule specifically for PoseEstimator.
Definition: PoseEstimatorModule.hpp:27
DetectedObject.hpp
CatkinResourceRetriever.hpp
PerceptionModule.hpp
aikido::perception::PoseEstimatorModule::mAssetData
std::shared_ptr< AssetDatabase > mAssetData
The pointer to the loader of visual asset data.
Definition: PoseEstimatorModule.hpp:76
aikido::perception::PoseEstimatorModule::mReferenceLink
dart::dynamics::Frame * mReferenceLink
The reference frame of HERB to transform with respect to.
Definition: PoseEstimatorModule.hpp:85
AssetDatabase.hpp