source: trunk/extremum_seeking/esc_ros/include/esc_ros/esc_ros.h @ 19

Last change on this file since 19 was 19, checked in by wcaarls, 11 years ago

Updated extremum_seeking to revision 1177

File size: 1.3 KB
Line 
1/*
2 * esc_ros.h
3 *
4 *  Created on: Jul 26, 2012
5 *      Author: Berk Calli, Wouter Caarls
6 *      Organization: Delft Biorobotics Lab., Delft University of Technology
7 *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
8 *
9 *      Header of the ROS wrapper for extremum seeking control nodes.
10 */
11
12#ifndef ESC_ROS_H_
13#define ESC_ROS_H_
14
15#include <ros/ros.h>
16#include <std_msgs/Float32.h>
17#include <std_msgs/Float32MultiArray.h>
18#include <std_msgs/Bool.h>
19#include <std_msgs/Empty.h>
20#include <esc_common/esc.h>
21#include <string>
22#include <esc_ros/Monitors.h>
23#include <esc_ros/StateValue.h>
24
25class ESCROS{
26protected:
27        ESC* esc_;
28        ros::Publisher pub_ref_, pub_monitor_, pub_stopped_;
29        ros::Subscriber sub_obj_val_, sub_enable_;
30        ros::NodeHandle* n_;
31        double obj_val_;
32        std::vector<double> state_vec_;
33        bool initialized_, monitor_, first_obj_val_received_,enabled_, reference_zeroed_;
34        double period_;
35        unsigned int opt_dim_;
36
37public:
38        ESCROS(ros::NodeHandle* n=NULL);
39        virtual void init(ESC* esc);
40        virtual void step();
41        virtual void spin();
42        virtual void reset();
43        virtual void enableCallback(std_msgs::Bool msg);
44        virtual ~ESCROS(){};
45protected:
46        virtual void objValCallback(std_msgs::Float32 msg);
47        virtual void objValWithStateCallback(esc_ros::StateValue msg);
48
49};
50
51
52
53
54#endif /* ESC_ROS_H_ */
Note: See TracBrowser for help on using the repository browser.