2018-06-26 18:27:30 +02:00
|
|
|
#ifndef RVIZINTERFACE_HPP
|
|
|
|
#define RVIZINTERFACE_HPP
|
|
|
|
|
|
|
|
#include <ros/ros.h>
|
|
|
|
|
|
|
|
#include <interactive_markers/interactive_marker_server.h>
|
|
|
|
#include <tf/tf.h>
|
|
|
|
|
|
|
|
#include "InteractiveObject.hpp"
|
|
|
|
|
|
|
|
#include <rviz_interface/InterfaceConfig.h>
|
|
|
|
|
|
|
|
class RvizInterface
|
|
|
|
{
|
|
|
|
protected:
|
|
|
|
ros::NodeHandle _n;
|
2018-07-02 11:09:50 +02:00
|
|
|
|
|
|
|
//Publisher ROS
|
2018-06-26 18:27:30 +02:00
|
|
|
ros::Publisher _objective_pub;
|
2018-06-28 14:40:20 +02:00
|
|
|
ros::Publisher _visualization_pub;
|
2018-07-02 11:09:50 +02:00
|
|
|
|
|
|
|
//Subscriber ROS
|
2018-06-26 18:27:30 +02:00
|
|
|
ros::Subscriber _config_sub;
|
2018-06-29 15:31:04 +02:00
|
|
|
ros::Subscriber _position_sub;
|
2018-06-28 14:40:20 +02:00
|
|
|
|
2018-07-02 11:09:50 +02:00
|
|
|
//Serveur de marker interactif
|
2018-06-26 18:27:30 +02:00
|
|
|
interactive_markers::InteractiveMarkerServer _server;
|
|
|
|
|
2018-07-02 11:09:50 +02:00
|
|
|
//Objets de l'interface
|
2018-06-26 18:27:30 +02:00
|
|
|
std::vector<InteractiveObject*> _objects;
|
|
|
|
|
|
|
|
public:
|
|
|
|
RvizInterface();
|
|
|
|
~RvizInterface();
|
|
|
|
|
2018-07-02 11:09:50 +02:00
|
|
|
//Fonction Callback du panel Rviz gérant les configurations
|
2018-06-26 18:27:30 +02:00
|
|
|
void configCallback(const rviz_interface::InterfaceConfig & new_config);
|
2018-07-02 11:09:50 +02:00
|
|
|
|
|
|
|
//Fonction callback gérant la position de l'objet
|
|
|
|
//PROVISOIRE : Pour un seul objet avec test PCL
|
2018-06-29 15:31:04 +02:00
|
|
|
void positionCallback(const geometry_msgs::PointStamped & new_center);
|
2018-06-26 18:27:30 +02:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif
|