33 #define PARAM_PULSE_STRING "/pulse" 68 int conversion = boost::lexical_cast<
int>(str_conversion);
75 int emod = boost::lexical_cast<
unsigned int>(str_pina);
81 int motors = (emod - command) >> 4;
82 int tmp1 = ((motors & 0b1) > 0);
83 int tmp2 = ((motors & 0b10) > 0);
86 for (vector<roboteq::Motor*>::iterator it =
_motor.begin() ; it !=
_motor.end(); ++it)
99 for (vector<roboteq::Motor*>::iterator it =
_motor.begin() ; it !=
_motor.end(); ++it)
118 int polarity = boost::lexical_cast<
int>(str_polarity);
124 int deadband = boost::lexical_cast<
int>(str_deadband);
130 double min = boost::lexical_cast<
double>(str_min) / 1000;
136 double max = boost::lexical_cast<
double>(str_max) / 1000;
142 double ctr = boost::lexical_cast<
double>(str_ctr) / 1000;
146 }
catch (std::bad_cast& e)
148 ROS_WARN_STREAM(
"Failure parsing feedback data. Dropping message." << e.what());
164 if(config.restore_defaults)
167 config.restore_defaults =
false;
172 if(config.load_roboteq)
175 config.load_roboteq =
false;
193 int input = config.input_use + 16*config.input_motor_one + 32*config.input_motor_two;
196 if(config.input_motor_one)
202 if(config.input_motor_two)
224 int range_input_min = config.range_input_min * 1000;
231 int range_input_max = config.range_input_max * 1000;
238 int range_input_center = config.range_input_center * 1000;
void getParamFromRoboteq()
getParamFromRoboteq Load parameters from Roboteq board
void reconfigureCBParam(roboteq_control::RoboteqPulseInputConfig &config, uint32_t level)
reconfigureCBParam when the dynamic reconfigurator change some values start this method ...
bool setParam(string msg, string params="")
bool setup_param
Setup variable.
roboteq::serial_controller * mSerial
Serial port.
#define PARAM_PULSE_STRING
dynamic_reconfigure::Server< roboteq_control::RoboteqPulseInputConfig > * ds_param
Dynamic reconfigure parameters.
ros::NodeHandle nh_
Private namespace.
std::vector< roboteq::Motor * > _motor
string getName()
getName the name of the motor
ROSLIB_DECL std::string command(const std::string &cmd)
const std::string & getNamespace() const
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
#define ROS_WARN_STREAM(args)
string mName
Associate name space.
roboteq_control::RoboteqPulseInputConfig default_param_config
int getNumber()
getNumber The roboteq number
string getParam(string msg, string params="")
void registerSensor(GPIOSensor *sensor)
registerSensor register the sensor
roboteq_control::RoboteqPulseInputConfig _last_param_config
#define ROS_INFO_STREAM(args)
GPIOPulseConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::vector< roboteq::Motor * > motor, string name, unsigned int number)
GPIOPulseConfigurator.
unsigned int mNumber
Number motor.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const