motor_controller_node.h
Go to the documentation of this file.
00001 #ifndef __MCDC3006S_NODE_H__
00002 #define __MCDC3006S_NODE_H__
00003 
00029 #include <iostream>
00030 #include <ros/ros.h>
00031 #include "motor_controller_data.h"
00032 
00033 // mcdc3006s driver
00034 #include "mcdc3006s.h"
00035 
00036 // messages and services
00037 #include <maggie_motor_controller_msgs/Data.h>
00038 #include <maggie_motor_controller_msgs/Odometry.h>
00039 #include <maggie_motor_controller_msgs/Configuration.h>
00040 #include <maggie_motor_controller_msgs/MoveAbsPos.h>
00041 
00042 class MotorControllerNode {
00043     public:
00047         MotorControllerNode(MotorDriverInterface *driver);
00048 
00052         ~MotorControllerNode();
00053 
00057         void init();
00058 
00062         void spin();
00063 
00065         // publishers
00067 
00071         void publish();
00072 
00074         // services
00076 
00083         bool set_max_pos(maggie_motor_controller_msgs::Configuration::Request & req,
00084                          maggie_motor_controller_msgs::Configuration::Response & resp);
00085 
00092         bool set_min_pos(maggie_motor_controller_msgs::Configuration::Request & req,
00093                          maggie_motor_controller_msgs::Configuration::Response & resp);
00094 
00101         bool set_max_vel(maggie_motor_controller_msgs::Configuration::Request & req,
00102                          maggie_motor_controller_msgs::Configuration::Response & resp);
00103 
00110         bool set_max_acc(maggie_motor_controller_msgs::Configuration::Request & req,
00111                          maggie_motor_controller_msgs::Configuration::Response & resp);
00112 
00119         bool set_max_dec(maggie_motor_controller_msgs::Configuration::Request & req,
00120                          maggie_motor_controller_msgs::Configuration::Response & resp);
00121 
00128         bool set_cur_lim(maggie_motor_controller_msgs::Configuration::Request & req,
00129                          maggie_motor_controller_msgs::Configuration::Response & resp);
00130 
00137         bool move_abs_pos(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00138                           maggie_motor_controller_msgs::MoveAbsPos::Response & resp);
00139 
00146         bool move_rel_pos(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00147                           maggie_motor_controller_msgs::MoveAbsPos::Response & resp);
00148 
00155         bool move_vel(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00156                       maggie_motor_controller_msgs::MoveAbsPos::Response & resp);
00157 
00164         bool joint_calibration(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00165                                maggie_motor_controller_msgs::MoveAbsPos::Response & resp);
00166 
00167     private:
00168         // nodes
00169         ros::NodeHandle _nh;
00170         ros::NodeHandle _nh_private;
00171 
00172         // publishers
00173         ros::Publisher _data_msg;
00174         ros::Publisher _odo_msg;
00175 
00176         // services
00177         ros::ServiceServer _max_pos_srv;
00178         ros::ServiceServer _min_pos_srv;
00179         ros::ServiceServer _max_vel_srv;
00180         ros::ServiceServer _max_acc_srv;
00181         ros::ServiceServer _max_dec_srv;
00182         ros::ServiceServer _cur_lim_srv;
00183         ros::ServiceServer _odo_srv;
00184         ros::ServiceServer _mov_abs_pos_srv;
00185         ros::ServiceServer _mov_rel_pos_srv;
00186         ros::ServiceServer _mov_vel_srv;
00187         ros::ServiceServer _calibration_srv;
00188 
00189         // spin rate
00190         ros::Rate _publish_rate;
00191 
00192         // ros params
00193         int _joint_id;
00194         std::string _serial_device, _joint_name;
00195 
00196         int _pos_factor, _vel_factor;
00197         float _calibration_home;
00198 
00199         MotorDriverInterface *_driver;
00200 };
00201 
00202 #endif


maggie_motor_controller
Author(s): Raul Perula-Martinez
autogenerated on Thu Apr 23 2015 22:19:04