Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include <esc_ros/esc_ros.h>
00012
00013
00014 ESCROS::ESCROS(ros::NodeHandle* n){
00015 n_ = n;
00016 initialized_ = false;
00017
00018 }
00019
00020 void ESCROS::init(ESC* esc)
00021 {
00022 if(!n_)
00023 n_ = new ros::NodeHandle();
00024
00025 reset();
00026 enabled_ = true;
00027 esc_ = esc;
00028
00029
00030 if (!n_->getParam("period", period_)){
00031 ROS_WARN("[nn_esc_1D]: Failed to get the parameter period from the parameter server. Using the default value.");
00032 period_ = 0;
00033 }
00034
00035 if (!n_->getParam("monitor", monitor_)){
00036 ROS_WARN("[nn_esc_1D]: Failed to get the parameter monitor from the parameter server. Using the default value.");
00037 monitor_ = false;
00038 }
00039 if(esc_->getInputType() == esc_->inputValue)
00040 sub_obj_val_ = n_->subscribe("obj_val", 1, &ESCROS::objValCallback, this);
00041 else if (esc_->getInputType() == esc_->inputStateValue)
00042 sub_obj_val_ = n_->subscribe("esc_in", 1, &ESCROS::objValWithStateCallback, this);
00043 else
00044 ROS_WARN("The input value is not specified. The subscriber will not be created.");
00045
00046 if(esc_->getOutputType() == esc_->outputVelocity)
00047 pub_ref_ = n_->advertise<std_msgs::Float32MultiArray>("vel_ref",1);
00048 else if(esc_->getOutputType() == esc_->outputPosition)
00049 pub_ref_ = n_->advertise<std_msgs::Float32MultiArray>("pos_ref",1);
00050 else
00051 ROS_WARN("The output value is not specified. The output of the ESC can not be published.");
00052
00053 if(monitor_){
00054 pub_monitor_ = n_->advertise<esc_ros::Monitors>("monitor_out",1);
00055 }
00056
00057 sub_enable_ = n_->subscribe("enable", 1, &ESCROS::enableCallback, this);
00058 pub_stopped_ = n_->advertise<std_msgs::Empty>("stopping_conditions_met",1);
00059 }
00060
00061 void ESCROS::objValWithStateCallback(esc_ros::StateValue msg)
00062 {
00063 obj_val_ = msg.value;
00064 state_vec_.resize(msg.state.size());
00065 for (size_t ii=0; ii < state_vec_.size(); ++ii)
00066 state_vec_[ii] = msg.state[ii];
00067 if(!first_obj_val_received_)
00068 first_obj_val_received_ = true;
00069 }
00070
00071 void ESCROS::objValCallback(std_msgs::Float32 msg)
00072 {
00073 obj_val_ = msg.data;
00074 if(!first_obj_val_received_)
00075 first_obj_val_received_ = true;
00076
00077 }
00078
00079 void ESCROS::reset(){
00080
00081 initialized_ = true;
00082 first_obj_val_received_ = false;
00083 reference_zeroed_ = false;
00084 opt_dim_ = 0;
00085 }
00086
00087 void ESCROS::enableCallback(std_msgs::Bool msg)
00088 {
00089 if (msg.data){
00090 reset();
00091 esc_->reset();
00092 enabled_ = true;
00093 ROS_INFO("[esc_ros]: ESC enabled.");
00094 }
00095 else
00096 enabled_ = false;
00097 }
00098
00099 void ESCROS::step()
00100 {
00101
00102 if(initialized_){
00103 if(first_obj_val_received_){
00104 if(enabled_){
00105 std::vector<double> out;
00106 if(esc_->getInputType() == esc_->inputValue)
00107 out = esc_->step(obj_val_);
00108 else if (esc_->getInputType() == esc_->inputStateValue)
00109 out = esc_->step(state_vec_,obj_val_);
00110 else
00111 ROS_WARN("Invalid input type for the extremum seeking controller. The step function will not be executed.");
00112
00113 if (out.empty()){
00114 return;
00115 }
00116 if(opt_dim_ == 0){
00117 opt_dim_ = out.size();
00118 }
00119
00120 std_msgs::Float32MultiArray msg;
00121 for(size_t i=0;i<out.size();i++)
00122 msg.data.push_back(out[i]);
00123 pub_ref_.publish(msg);
00124
00125 if(monitor_){
00126 esc_ros::Monitors msg_monitor;
00127 std::vector<double> values = esc_->monitor();
00128
00129 msg_monitor.values.resize(values.size());
00130 for (size_t ii=0; ii < values.size(); ++ii)
00131 msg_monitor.values[ii] = values[ii];
00132 msg_monitor.names = esc_->monitorNames();
00133 pub_monitor_.publish(msg_monitor);
00134 }
00135 }
00136 else if(!reference_zeroed_){
00137
00138 std_msgs::Float32MultiArray msg;
00139
00140 if (opt_dim_ != 0){
00141 msg.data.resize(opt_dim_);
00142
00143 for(size_t i = 0; i<opt_dim_; i++)
00144 msg.data[i] = 0;
00145
00146 pub_ref_.publish(msg);
00147 opt_dim_ = 0;
00148 }
00149 reference_zeroed_ = true;
00150
00151 }
00152
00153 }
00154
00155 }
00156 else
00157 ROS_WARN("ESC class is not initialized. Its functions will not be executed.");
00158 }
00159
00160 void ESCROS::spin()
00161 {
00162 ros::Rate loop_rate(1.0/period_);
00163
00164 while (n_->ok()) {
00165 if(esc_->isStoppingConditionsMet()){
00166 std_msgs::Empty msg_stopped;
00167 pub_stopped_.publish(msg_stopped);
00168 enabled_ = false;
00169 }
00170 step();
00171 ros::spinOnce();
00172 loop_rate.sleep();
00173 }
00174 }