1 #ifndef OBJECT_TRACKER_OBJECT_TRACKER_H 2 #define OBJECT_TRACKER_OBJECT_TRACKER_H 6 #include <std_msgs/String.h> 7 #include <std_msgs/Float32.h> 9 #include <hector_worldmodel_msgs/SetObjectState.h> 10 #include <hector_worldmodel_msgs/SetObjectName.h> 11 #include <hector_worldmodel_msgs/AddObject.h> 12 #include <hector_worldmodel_msgs/GetObjectModel.h> 13 #include <sensor_msgs/CameraInfo.h> 31 void imagePerceptCb(
const hector_worldmodel_msgs::ImagePerceptConstPtr &);
32 void posePerceptCb(
const hector_worldmodel_msgs::PosePerceptConstPtr &);
35 void modelUpdateCb(
const hector_worldmodel_msgs::ObjectModelConstPtr &);
37 bool setObjectStateCb(hector_worldmodel_msgs::SetObjectState::Request& request, hector_worldmodel_msgs::SetObjectState::Response& response);
38 bool setObjectNameCb(hector_worldmodel_msgs::SetObjectName::Request& request, hector_worldmodel_msgs::SetObjectName::Response& response);
39 bool addObjectCb(hector_worldmodel_msgs::AddObject::Request& request, hector_worldmodel_msgs::AddObject::Response& response);
40 bool getObjectModelCb(hector_worldmodel_msgs::GetObjectModel::Request& request, hector_worldmodel_msgs::GetObjectModel::Response& response);
52 bool transformPose(
const geometry_msgs::PoseWithCovariance& from, geometry_msgs::PoseWithCovariance &to, std_msgs::Header &header);
53 bool mapToNextObstacle(
const geometry_msgs::Pose& source,
const std_msgs::Header &header,
const ObjectInfo &info, geometry_msgs::Pose &mapped);
106 void mergeModelCallback(
const hector_worldmodel_msgs::ObjectModelConstPtr &new_model,
const MergedModelPtr& info);
117 #endif // OBJECT_TRACKER_OBJECT_TRACKER_H
bool transformPose(const geometry_msgs::Pose &from, geometry_msgs::Pose &to, std_msgs::Header &header, tf::StampedTransform *transform=0)
ros::Subscriber subscriber
ros::Publisher objectPoseDebugPublisher
ros::Subscriber sysCommandSubscriber
void publishModelEvent(const ros::TimerEvent &)
ros::Subscriber objectAgeingSubscriber
ros::Duration not_seen_duration
ros::ServiceServer addObject
void imagePerceptCb(const hector_worldmodel_msgs::ImagePerceptConstPtr &)
boost::shared_ptr< NegativeUpdateInfo > NegativeUpdatePtr
std::map< std::string, CameraModelPtr > cameraModels
const ObjectModel & getModel() const
bool setObjectNameCb(hector_worldmodel_msgs::SetObjectName::Request &request, hector_worldmodel_msgs::SetObjectName::Response &response)
boost::shared_ptr< MergedModelInfo > MergedModelPtr
float ignore_border_pixels
std::vector< NegativeUpdatePtr > negativeUpdate
void sysCommandCb(const std_msgs::StringConstPtr &)
ros::ServiceServer getObjectModel
std::vector< MergedModelPtr > merged_models
ObjectInfo::_support_type min_support
ObjectModel getMergedModel()
boost::shared_ptr< image_geometry::PinholeCameraModel > CameraModelPtr
void modelUpdateCb(const hector_worldmodel_msgs::ObjectModelConstPtr &)
bool addObjectCb(hector_worldmodel_msgs::AddObject::Request &request, hector_worldmodel_msgs::AddObject::Response &response)
void negativeUpdateCallback(const sensor_msgs::CameraInfoConstPtr &, const NegativeUpdatePtr &info)
void mergeModelCallback(const hector_worldmodel_msgs::ObjectModelConstPtr &new_model, const MergedModelPtr &info)
ros::Subscriber posePerceptSubscriber
ObjectTracker::CameraModelPtr getCameraModel(const std::string &frame_id, const sensor_msgs::CameraInfo &camera_info)
std::string _worldmodel_ns
bool mapToNextObstacle(const geometry_msgs::Pose &source, const std_msgs::Header &header, const ObjectInfo &info, geometry_msgs::Pose &mapped)
void posePerceptCb(const hector_worldmodel_msgs::PosePerceptConstPtr &)
ros::Publisher modelUpdatePublisher
ros::Publisher modelPublisher
ros::ServiceServer setObjectName
ros::Publisher perceptPoseDebugPublisher
ros::Subscriber imagePerceptSubscriber
ros::Subscriber subscriber
ros::Subscriber modelUpdateSubscriber
ros::ServiceServer setObjectState
void objectAgeingCb(const std_msgs::Float32ConstPtr &)
bool setObjectStateCb(hector_worldmodel_msgs::SetObjectState::Request &request, hector_worldmodel_msgs::SetObjectState::Response &response)
bool getObjectModelCb(hector_worldmodel_msgs::GetObjectModel::Request &request, hector_worldmodel_msgs::GetObjectModel::Response &response)
ObjectInfo::_support_type negative_support