Public Member Functions | Private Attributes
MotorControllerNode Class Reference

#include <motor_controller_node.h>

List of all members.

Public Member Functions

void init ()
 Initialize the mcdc3006s node.
bool joint_calibration (maggie_motor_controller_msgs::MoveAbsPos::Request &req, maggie_motor_controller_msgs::MoveAbsPos::Response &resp)
 Callback to calibrate the joint.
 MotorControllerNode (MotorDriverInterface *driver)
 Empty constructor.
bool move_abs_pos (maggie_motor_controller_msgs::MoveAbsPos::Request &req, maggie_motor_controller_msgs::MoveAbsPos::Response &resp)
 Callback to move motors by absolute position.
bool move_rel_pos (maggie_motor_controller_msgs::MoveAbsPos::Request &req, maggie_motor_controller_msgs::MoveAbsPos::Response &resp)
 Callback to move motors by relative position.
bool move_vel (maggie_motor_controller_msgs::MoveAbsPos::Request &req, maggie_motor_controller_msgs::MoveAbsPos::Response &resp)
 Callback to move motors in velocity.
void publish ()
 Publish information from the motors.
bool set_cur_lim (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the current limit of the motor.
bool set_max_acc (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the maximum acceleration of the motor.
bool set_max_dec (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the maximum deceleration of the motor.
bool set_max_pos (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the maximum position of the motor.
bool set_max_vel (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the maximum velocity of the motor.
bool set_min_pos (maggie_motor_controller_msgs::Configuration::Request &req, maggie_motor_controller_msgs::Configuration::Response &resp)
 Callback to set the minimum position of the motor.
void spin ()
 Spin the node.
 ~MotorControllerNode ()
 Destructor.

Private Attributes

float _calibration_home
ros::ServiceServer _calibration_srv
ros::ServiceServer _cur_lim_srv
ros::Publisher _data_msg
MotorDriverInterface * _driver
int _joint_id
std::string _joint_name
ros::ServiceServer _max_acc_srv
ros::ServiceServer _max_dec_srv
ros::ServiceServer _max_pos_srv
ros::ServiceServer _max_vel_srv
ros::ServiceServer _min_pos_srv
ros::ServiceServer _mov_abs_pos_srv
ros::ServiceServer _mov_rel_pos_srv
ros::ServiceServer _mov_vel_srv
ros::NodeHandle _nh
ros::NodeHandle _nh_private
ros::Publisher _odo_msg
ros::ServiceServer _odo_srv
int _pos_factor
ros::Rate _publish_rate
std::string _serial_device
int _vel_factor

Detailed Description

Definition at line 42 of file motor_controller_node.h.


Constructor & Destructor Documentation

MotorControllerNode::MotorControllerNode ( MotorDriverInterface *  driver)

Empty constructor.

Definition at line 30 of file motor_controller_node.cpp.

Destructor.

Definition at line 127 of file motor_controller_node.cpp.


Member Function Documentation

Initialize the mcdc3006s node.

Definition at line 134 of file motor_controller_node.cpp.

bool MotorControllerNode::joint_calibration ( maggie_motor_controller_msgs::MoveAbsPos::Request &  req,
maggie_motor_controller_msgs::MoveAbsPos::Response &  resp 
)

Callback to calibrate the joint.

Parameters:
reqCalibration type request.
respCalibration type response.
Returns:
true if there are no errors.

Definition at line 354 of file motor_controller_node.cpp.

bool MotorControllerNode::move_abs_pos ( maggie_motor_controller_msgs::MoveAbsPos::Request &  req,
maggie_motor_controller_msgs::MoveAbsPos::Response &  resp 
)

Callback to move motors by absolute position.

Parameters:
reqMoveAbsPos type request.
respMoveAbsPos type response.
Returns:
true if there are no errors.

Definition at line 308 of file motor_controller_node.cpp.

bool MotorControllerNode::move_rel_pos ( maggie_motor_controller_msgs::MoveAbsPos::Request &  req,
maggie_motor_controller_msgs::MoveAbsPos::Response &  resp 
)

Callback to move motors by relative position.

Parameters:
reqMoveAbsPos type request.
respMoveAbsPos type response.
Returns:
true if there are no errors.

Definition at line 323 of file motor_controller_node.cpp.

bool MotorControllerNode::move_vel ( maggie_motor_controller_msgs::MoveAbsPos::Request &  req,
maggie_motor_controller_msgs::MoveAbsPos::Response &  resp 
)

Callback to move motors in velocity.

Parameters:
reqMoveAbsPos type request.
respMoveAbsPos type response.
Returns:
true if there are no errors.

Definition at line 338 of file motor_controller_node.cpp.

Publish information from the motors.

Definition at line 171 of file motor_controller_node.cpp.

bool MotorControllerNode::set_cur_lim ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the current limit of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 296 of file motor_controller_node.cpp.

bool MotorControllerNode::set_max_acc ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the maximum acceleration of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 270 of file motor_controller_node.cpp.

bool MotorControllerNode::set_max_dec ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the maximum deceleration of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 283 of file motor_controller_node.cpp.

bool MotorControllerNode::set_max_pos ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the maximum position of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 230 of file motor_controller_node.cpp.

bool MotorControllerNode::set_max_vel ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the maximum velocity of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 257 of file motor_controller_node.cpp.

bool MotorControllerNode::set_min_pos ( maggie_motor_controller_msgs::Configuration::Request &  req,
maggie_motor_controller_msgs::Configuration::Response &  resp 
)

Callback to set the minimum position of the motor.

Parameters:
reqConfiguration type request.
respConfiguration type response.
Returns:
true if there are no errors.

Definition at line 244 of file motor_controller_node.cpp.

Spin the node.

Definition at line 158 of file motor_controller_node.cpp.


Member Data Documentation

Definition at line 197 of file motor_controller_node.h.

Definition at line 187 of file motor_controller_node.h.

Definition at line 182 of file motor_controller_node.h.

Definition at line 173 of file motor_controller_node.h.

MotorDriverInterface* MotorControllerNode::_driver [private]

Definition at line 199 of file motor_controller_node.h.

Definition at line 193 of file motor_controller_node.h.

std::string MotorControllerNode::_joint_name [private]

Definition at line 194 of file motor_controller_node.h.

Definition at line 180 of file motor_controller_node.h.

Definition at line 181 of file motor_controller_node.h.

Definition at line 177 of file motor_controller_node.h.

Definition at line 179 of file motor_controller_node.h.

Definition at line 178 of file motor_controller_node.h.

Definition at line 184 of file motor_controller_node.h.

Definition at line 185 of file motor_controller_node.h.

Definition at line 186 of file motor_controller_node.h.

Definition at line 169 of file motor_controller_node.h.

Definition at line 170 of file motor_controller_node.h.

Definition at line 174 of file motor_controller_node.h.

Definition at line 183 of file motor_controller_node.h.

Definition at line 196 of file motor_controller_node.h.

Definition at line 190 of file motor_controller_node.h.

std::string MotorControllerNode::_serial_device [private]

Definition at line 194 of file motor_controller_node.h.

Definition at line 196 of file motor_controller_node.h.


The documentation for this class was generated from the following files:


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