Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
motoman::controller::Controller Class Reference

Class encapsulates the motoman controller interface. It also handles higher level functions such as maintining the current motion state. This class is meant to be a Singleton, but that is not explicitly enforced. Only one instance of this object should be instantiated. More...

#include <controller.h>

List of all members.

Public Member Functions

 Controller ()
 Default controller.
 Controller ()
 Default controller.
void delayTicks (int ticks)
 Stops motion job on the controller. Disables motion.
void delayTicks (int ticks)
 Stops motion job on the controller. Disables motion.
void disableMotion (void)
 Disables motion on the robot controller. Turns off servo power, turns on hold status.
void disableMotion (void)
 Disables motion on the robot controller. Turns off servo power, turns on hold status.
void enableMotion (void)
 Enables motion on the robot controller. Turns on servo power, turns off hold status.
void enableMotion (void)
 Enables motion on the robot controller. Turns on servo power, turns off hold status.
bool getStatus (industrial::robot_status::RobotStatus &status)
 Gets the current robot status from the controller.
bool getStatus (industrial::robot_status::RobotStatus &status)
 Gets the current robot status from the controller.
double getVelocityLimit ()
 Returns the velocity limit set for the controller. This is stored within the integer data table at VELOCITY_LIMIT_INDEX.
double getVelocityLimit ()
 Returns the velocity limit set for the controller. This is stored within the integer data table at VELOCITY_LIMIT_INDEX.
bool isJobStarted (void)
 return true if jos has been started (Based on internal class state not MotoPlus call)
bool isJobStarted (void)
 return true if jos has been started (Based on internal class state not MotoPlus call)
bool isMotionEnabled (void)
 return true if motion is enabled (Based on internal class state not MotoPlus call)
bool isMotionEnabled (void)
 return true if motion is enabled (Based on internal class state not MotoPlus call)
bool loadJob (char *path, char *job)
 Utility function for loading a job file from temporary DRAM (the memory supported by all controllers) WARNING: This function is limited to the DRAM root directory.
bool loadJob (char *path, char *job)
 Utility function for loading a job file from temporary DRAM (the memory supported by all controllers) WARNING: This function is limited to the DRAM root directory.
void setDigitalOut (int bit_offset, bool value)
 Utility function for setting a digital output in the Universal output data table (most IO is accessible there).
void setDigitalOut (int bit_offset, bool value)
 Utility function for setting a digital output in the Universal output data table (most IO is accessible there).
void startMotionJob (char *job_name)
 Starts motion job on the controller. Enables motion (Job cannot be started if motion is not enabled).
void startMotionJob (char *job_name)
 Starts motion job on the controller. Enables motion (Job cannot be started if motion is not enabled).
void stopMotionJob (char *job_name)
 Stops motion job on the controller. Disables motion.
void stopMotionJob (char *job_name)
 Stops motion job on the controller. Disables motion.
void waitDigitalIn (int bit_offset, bool wait_value)
 Utility function for waiting for a digital input in the Universal input data tabel (most IO is accessible there).
void waitDigitalIn (int bit_offset, bool wait_value)
 Utility function for waiting for a digital input in the Universal input data tabel (most IO is accessible there).
bool writeJob (char *path, char *job)
 Utility function for writing a job file in temporary DRAM (the memory supported by all controllers)
bool writeJob (char *path, char *job)
 Utility function for writing a job file in temporary DRAM (the memory supported by all controllers)
 ~Controller ()
 Destructor (disables motion and stops current job);.
 ~Controller ()
 Destructor (disables motion and stops current job);.

Static Public Member Functions

static bool getActJointPos (float *pos)
 Get the actual Joint Position from the robot encoders NOTE: use getCmdJointPos to get the commanded joint positions.
static bool getActJointPos (float *pos)
 Get the actual Joint Position from the robot encoders NOTE: use getCmdJointPos to get the commanded joint positions.
static int getCtrlGroup ()
static int getCtrlGroup ()
static bool getFBPulseCorrection (int ctrl_grp, FB_AXIS_CORRECTION *pulse_correction)
 Reads the pulse correction factors from the controller's config parameters, based on physical axis cross-coupling. pulsePos[ulCorrectionAxis] -= pulsePos[ulSourceAxis] * fCorrectionRatio.
static bool getFBPulseCorrection (int ctrl_grp, FB_AXIS_CORRECTION *pulse_correction)
 Reads the pulse correction factors from the controller's config parameters, based on physical axis cross-coupling. pulsePos[ulCorrectionAxis] -= pulsePos[ulSourceAxis] * fCorrectionRatio.
static bool getFBPulseCorrection (FB_AXIS_CORRECTION *pulse_correction)
static bool getFBPulseCorrection (FB_AXIS_CORRECTION *pulse_correction)
static bool getIncrMotionLimit (int ctrl_grp, float *limit)
 Reads the maximum percentage (of maxIncrPerCycle) allowed for commanded motion from the controller's config parameters.
static bool getIncrMotionLimit (int ctrl_grp, float *limit)
 Reads the maximum percentage (of maxIncrPerCycle) allowed for commanded motion from the controller's config parameters.
static bool getIncrMotionLimit (float *limit)
static bool getIncrMotionLimit (float *limit)
static int getInteger (int index)
 Read integer data from the controller integer data table. Function blocks until data is read.
static int getInteger (int index)
 Read integer data from the controller integer data table. Function blocks until data is read.
static bool getInterpPeriod (UINT16 *interp_period)
 Reads the number of milliseconds between each tick of the interpolation clock from the controller's config parameters.
static bool getInterpPeriod (UINT16 *interp_period)
 Reads the number of milliseconds between each tick of the interpolation clock from the controller's config parameters.
static bool getMaxIncrPerCycle (int ctrl_grp, int *max_incr)
 Reads the max increment each joint can move per interpolation cycle from the controller's config parameters.
static bool getMaxIncrPerCycle (int ctrl_grp, int *max_incr)
 Reads the max increment each joint can move per interpolation cycle from the controller's config parameters.
static bool getMaxIncrPerCycle (int *max_incr)
static bool getMaxIncrPerCycle (int *max_incr)
static bool getNumRobotAxes (int ctrl_grp, int *numAxes)
 Reads the number of robot axes from the controller's config parameters.
static bool getNumRobotAxes (int ctrl_grp, int *numAxes)
 Reads the number of robot axes from the controller's config parameters.
static bool getNumRobotAxes (int *numAxes)
static bool getNumRobotAxes (int *numAxes)
static bool getNumTasks (int *num_normal_tasks, int *num_highPrio_tasks, int *num_out_files)
 Reads the number of allowed tasks from the controller's config parameters.
static bool getNumTasks (int *num_normal_tasks, int *num_highPrio_tasks, int *num_out_files)
 Reads the number of allowed tasks from the controller's config parameters.
static bool getPulsesPerRadian (int ctrl_grp, float *pulses_per_radian)
 Reads the pulse-per-radian scaling factors from the controller's config parameters, based on the arm's gearing ratios. jntPosInRadians = jntPosInPulses * pulseToRadian.
static bool getPulsesPerRadian (int ctrl_grp, float *pulses_per_radian)
 Reads the pulse-per-radian scaling factors from the controller's config parameters, based on the arm's gearing ratios. jntPosInRadians = jntPosInPulses * pulseToRadian.
static bool getPulsesPerRadian (float *pulses_per_radian)
static bool getPulsesPerRadian (float *pulses_per_radian)
static bool initParameters (int ctrl_grp=0)
 Reads key values from parameter data-list.
static bool initParameters (int ctrl_grp=0)
 Reads key values from parameter data-list.
static void setCtrlGroup (int ctrl_grp)
static void setCtrlGroup (int ctrl_grp)
static void setInteger (int index, int value)
 Write integer data to the controller integer data table. Function blocks until data is written.
static void setInteger (int index, int value)
 Write integer data to the controller integer data table. Function blocks until data is written.
static bool setJointPositionVar (int index, industrial::joint_data::JointData ros_joints)
 Write position-variable data to the controller data table. Function blocks until data is written.
static bool setJointPositionVar (int index, industrial::joint_data::JointData ros_joints)
 Write position-variable data to the controller data table. Function blocks until data is written.

Protected Member Functions

industrial::robot_status::TriState getInMotionStatus ()
 Gets the current in motion status from the controller. The funciton queries the actual joint speeds so it should be independent of any program state (which should be more reliable).
industrial::robot_status::TriState getInMotionStatus ()
 Gets the current in motion status from the controller. The funciton queries the actual joint speeds so it should be independent of any program state (which should be more reliable).

Static Protected Member Functions

static bool is_bit_set (int i, param_func_t type)
static bool is_bit_set (int i, param_func_t type)
static bool is_valid_ctrl_grp (int ctrl_grp)
static bool is_valid_ctrl_grp (int ctrl_grp)
static void set_bit (int *i, param_func_t type)
static void set_bit (int *i, param_func_t type)

Protected Attributes

MP_HOLD_SEND_DATA hold_data
MP_STD_RSP_DATA hold_error
MP_DELETE_JOB_SEND_DATA job_delete_data
MP_STD_RSP_DATA job_error
MP_START_JOB_SEND_DATA job_start_data
bool jobStarted
 True if job started.
bool motionEnabled
 True if motion enabled.
MP_SERVO_POWER_SEND_DATA servo_power_data
MP_STD_RSP_DATA servo_power_error

Static Protected Attributes

static int active_ctrl_grp_ = 0
static const int MP_ERROR = -1
 Typical MP function call return on error.
static const int MP_OK = 0
 Typical MP function call return on OK (sometimes a value greater than zero is also returned if it has some meaning, like a file descriptor.
static const int UNIV_IN_DATA_START_ = 10
static const int UNIV_IO_DATA_SIZE_ = 2048
static const int UNIV_OUT_DATA_START_ = 10010
static const int VAR_POLL_DELAY_ = 10
 Poll delay (in ticks) when querying the motoplus api.
static const int VELOCITY_LIMIT_INDEX = 94
 Index within integer data table that holds velocity limit.

Detailed Description

Class encapsulates the motoman controller interface. It also handles higher level functions such as maintining the current motion state. This class is meant to be a Singleton, but that is not explicitly enforced. Only one instance of this object should be instantiated.

THIS CLASS IS NOT THREAD-SAFE (the methods that simply wrap motoplus calls can be considered thread safe). Some internal class state data is maintained, which is not thread safe. TODO: This class will likely be shared between threads, it should be made thread safe.

Definition at line 108 of file controller.h.


Constructor & Destructor Documentation

Default controller.

Definition at line 52 of file controller.cpp.

Destructor (disables motion and stops current job);.

Definition at line 58 of file controller.cpp.

Default controller.

Destructor (disables motion and stops current job);.


Member Function Documentation

void motoman::controller::Controller::delayTicks ( int  ticks) [inline]

Stops motion job on the controller. Disables motion.

Parameters:
ticks# of ticks to delay

Definition at line 252 of file controller.h.

void motoman::controller::Controller::delayTicks ( int  ticks) [inline]

Stops motion job on the controller. Disables motion.

Parameters:
ticks# of ticks to delay

Definition at line 252 of file output/controller.h.

Disables motion on the robot controller. Turns off servo power, turns on hold status.

Definition at line 248 of file controller.cpp.

Disables motion on the robot controller. Turns off servo power, turns on hold status.

Enables motion on the robot controller. Turns on servo power, turns off hold status.

Enables motion on the robot controller. Turns on servo power, turns off hold status.

Definition at line 224 of file controller.cpp.

bool motoman::controller::Controller::getActJointPos ( float *  pos) [static]

Get the actual Joint Position from the robot encoders NOTE: use getCmdJointPos to get the commanded joint positions.

Parameters:
posarray to hold joint positions (in radians)
Returns:
true if positions retrieved successfully

Definition at line 466 of file controller.cpp.

static bool motoman::controller::Controller::getActJointPos ( float *  pos) [static]

Get the actual Joint Position from the robot encoders NOTE: use getCmdJointPos to get the commanded joint positions.

Parameters:
posarray to hold joint positions (in radians)
Returns:
true if positions retrieved successfully
static int motoman::controller::Controller::getCtrlGroup ( ) [inline, static]

Definition at line 369 of file output/controller.h.

static int motoman::controller::Controller::getCtrlGroup ( ) [inline, static]

Definition at line 369 of file controller.h.

bool motoman::controller::Controller::getFBPulseCorrection ( int  ctrl_grp,
FB_AXIS_CORRECTION pulse_correction 
) [static]

Reads the pulse correction factors from the controller's config parameters, based on physical axis cross-coupling. pulsePos[ulCorrectionAxis] -= pulsePos[ulSourceAxis] * fCorrectionRatio.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]pulse_correctionarray of correction factors (length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read

Definition at line 563 of file controller.cpp.

static bool motoman::controller::Controller::getFBPulseCorrection ( int  ctrl_grp,
FB_AXIS_CORRECTION pulse_correction 
) [static]

Reads the pulse correction factors from the controller's config parameters, based on physical axis cross-coupling. pulsePos[ulCorrectionAxis] -= pulsePos[ulSourceAxis] * fCorrectionRatio.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]pulse_correctionarray of correction factors (length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read
static bool motoman::controller::Controller::getFBPulseCorrection ( FB_AXIS_CORRECTION pulse_correction) [inline, static]

Definition at line 322 of file controller.h.

static bool motoman::controller::Controller::getFBPulseCorrection ( FB_AXIS_CORRECTION pulse_correction) [inline, static]

Definition at line 322 of file output/controller.h.

static bool motoman::controller::Controller::getIncrMotionLimit ( int  ctrl_grp,
float *  limit 
) [static]

Reads the maximum percentage (of maxIncrPerCycle) allowed for commanded motion from the controller's config parameters.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]limitpercentage of MaxIncrPerCycle allowed for commanded motion
Returns:
true if parameters successfully read
bool motoman::controller::Controller::getIncrMotionLimit ( int  ctrl_grp,
float *  limit 
) [static]

Reads the maximum percentage (of maxIncrPerCycle) allowed for commanded motion from the controller's config parameters.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]limitpercentage of MaxIncrPerCycle allowed for commanded motion
Returns:
true if parameters successfully read

Definition at line 667 of file controller.cpp.

static bool motoman::controller::Controller::getIncrMotionLimit ( float *  limit) [inline, static]

Definition at line 367 of file output/controller.h.

static bool motoman::controller::Controller::getIncrMotionLimit ( float *  limit) [inline, static]

Definition at line 367 of file controller.h.

Gets the current in motion status from the controller. The funciton queries the actual joint speeds so it should be independent of any program state (which should be more reliable).

Returns:
motion status

Definition at line 185 of file controller.cpp.

Gets the current in motion status from the controller. The funciton queries the actual joint speeds so it should be independent of any program state (which should be more reliable).

Returns:
motion status
static int motoman::controller::Controller::getInteger ( int  index) [static]

Read integer data from the controller integer data table. Function blocks until data is read.

Parameters:
indexindex in data table
Returns:
integer value
int motoman::controller::Controller::getInteger ( int  index) [static]

Read integer data from the controller integer data table. Function blocks until data is read.

Parameters:
indexindex in data table
Returns:
integer value

Definition at line 129 of file controller.cpp.

bool motoman::controller::Controller::getInterpPeriod ( UINT16 *  interp_period) [static]

Reads the number of milliseconds between each tick of the interpolation clock from the controller's config parameters.

Parameters:
[out]interp_periodperiod between interpolation ticks (msec)
Returns:
true if parameters successfully read

Definition at line 617 of file controller.cpp.

static bool motoman::controller::Controller::getInterpPeriod ( UINT16 *  interp_period) [static]

Reads the number of milliseconds between each tick of the interpolation clock from the controller's config parameters.

Parameters:
[out]interp_periodperiod between interpolation ticks (msec)
Returns:
true if parameters successfully read
static bool motoman::controller::Controller::getMaxIncrPerCycle ( int  ctrl_grp,
int *  max_incr 
) [static]

Reads the max increment each joint can move per interpolation cycle from the controller's config parameters.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]max_incrarray of maximum increment values for each joint (length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read
bool motoman::controller::Controller::getMaxIncrPerCycle ( int  ctrl_grp,
int *  max_incr 
) [static]

Reads the max increment each joint can move per interpolation cycle from the controller's config parameters.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]max_incrarray of maximum increment values for each joint (length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read

Definition at line 637 of file controller.cpp.

static bool motoman::controller::Controller::getMaxIncrPerCycle ( int *  max_incr) [inline, static]

Definition at line 355 of file output/controller.h.

static bool motoman::controller::Controller::getMaxIncrPerCycle ( int *  max_incr) [inline, static]

Definition at line 355 of file controller.h.

bool motoman::controller::Controller::getNumRobotAxes ( int  ctrl_grp,
int *  numAxes 
) [static]

Reads the number of robot axes from the controller's config parameters.

Parameters:
ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
numAxesNumber of robot axes (return)
Returns:
true if parameters successfully read

Definition at line 518 of file controller.cpp.

static bool motoman::controller::Controller::getNumRobotAxes ( int  ctrl_grp,
int *  numAxes 
) [static]

Reads the number of robot axes from the controller's config parameters.

Parameters:
ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
numAxesNumber of robot axes (return)
Returns:
true if parameters successfully read
static bool motoman::controller::Controller::getNumRobotAxes ( int *  numAxes) [inline, static]

Definition at line 296 of file controller.h.

static bool motoman::controller::Controller::getNumRobotAxes ( int *  numAxes) [inline, static]

Definition at line 296 of file output/controller.h.

bool motoman::controller::Controller::getNumTasks ( int *  num_normal_tasks,
int *  num_highPrio_tasks,
int *  num_out_files 
) [static]

Reads the number of allowed tasks from the controller's config parameters.

Parameters:
[out]num_normal_tasksnumber of normal-priority tasks
[out]num_highPrio_tasksnumber of high-priority tasks
[out]num_out_filesnumber of output files (??)
Returns:
true if parameters successfully read

Definition at line 591 of file controller.cpp.

static bool motoman::controller::Controller::getNumTasks ( int *  num_normal_tasks,
int *  num_highPrio_tasks,
int *  num_out_files 
) [static]

Reads the number of allowed tasks from the controller's config parameters.

Parameters:
[out]num_normal_tasksnumber of normal-priority tasks
[out]num_highPrio_tasksnumber of high-priority tasks
[out]num_out_filesnumber of output files (??)
Returns:
true if parameters successfully read
static bool motoman::controller::Controller::getPulsesPerRadian ( int  ctrl_grp,
float *  pulses_per_radian 
) [static]

Reads the pulse-per-radian scaling factors from the controller's config parameters, based on the arm's gearing ratios. jntPosInRadians = jntPosInPulses * pulseToRadian.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]pulse_to_radianarray of scaling factors (in Motoman order, length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read
bool motoman::controller::Controller::getPulsesPerRadian ( int  ctrl_grp,
float *  pulses_per_radian 
) [static]

Reads the pulse-per-radian scaling factors from the controller's config parameters, based on the arm's gearing ratios. jntPosInRadians = jntPosInPulses * pulseToRadian.

Parameters:
[in]ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
[out]pulse_to_radianarray of scaling factors (in Motoman order, length=MAX_PULSE_AXES)
Returns:
true if parameters successfully read

Definition at line 535 of file controller.cpp.

static bool motoman::controller::Controller::getPulsesPerRadian ( float *  pulses_per_radian) [inline, static]

Definition at line 309 of file controller.h.

static bool motoman::controller::Controller::getPulsesPerRadian ( float *  pulses_per_radian) [inline, static]

Definition at line 309 of file output/controller.h.

Gets the current robot status from the controller.

Parameters:
statusrobot status data structure.
Returns:
true if robot status successfully retrieved.

Definition at line 177 of file controller.cpp.

Gets the current robot status from the controller.

Parameters:
statusrobot status data structure.
Returns:
true if robot status successfully retrieved.

Returns the velocity limit set for the controller. This is stored within the integer data table at VELOCITY_LIMIT_INDEX.

Returns:
velocity limit (%)

Definition at line 283 of file output/controller.h.

Returns the velocity limit set for the controller. This is stored within the integer data table at VELOCITY_LIMIT_INDEX.

Returns:
velocity limit (%)

Definition at line 283 of file controller.h.

static bool motoman::controller::Controller::initParameters ( int  ctrl_grp = 0) [static]

Reads key values from parameter data-list.

Parameters:
ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
Returns:
true if parameters successfully read
bool motoman::controller::Controller::initParameters ( int  ctrl_grp = 0) [static]

Reads key values from parameter data-list.

Parameters:
ctrl_grpRobot Control Group to retrieve. Zero-based (i.e. 0 = Control Group 1)
Returns:
true if parameters successfully read

Definition at line 64 of file controller.cpp.

static bool motoman::controller::Controller::is_bit_set ( int  i,
param_func_t  type 
) [inline, static, protected]

Definition at line 437 of file controller.h.

static bool motoman::controller::Controller::is_bit_set ( int  i,
param_func_t  type 
) [inline, static, protected]

Definition at line 437 of file output/controller.h.

bool motoman::controller::Controller::is_valid_ctrl_grp ( int  ctrl_grp) [static, protected]

Definition at line 510 of file controller.cpp.

static bool motoman::controller::Controller::is_valid_ctrl_grp ( int  ctrl_grp) [static, protected]

return true if jos has been started (Based on internal class state not MotoPlus call)

Returns:
true if job has been stared

Definition at line 218 of file output/controller.h.

return true if jos has been started (Based on internal class state not MotoPlus call)

Returns:
true if job has been stared

Definition at line 218 of file controller.h.

return true if motion is enabled (Based on internal class state not MotoPlus call)

Returns:
true if motion enabled

Definition at line 210 of file output/controller.h.

return true if motion is enabled (Based on internal class state not MotoPlus call)

Returns:
true if motion enabled

Definition at line 210 of file controller.h.

bool motoman::controller::Controller::loadJob ( char *  path,
char *  job 
)

Utility function for loading a job file from temporary DRAM (the memory supported by all controllers) WARNING: This function is limited to the DRAM root directory.

Parameters:
pathpath of the file to load (pass "" if the root directory is used)
jobname of file to load (may not work with a full path)
Returns:
true if job successfully loaded

Definition at line 384 of file controller.cpp.

bool motoman::controller::Controller::loadJob ( char *  path,
char *  job 
)

Utility function for loading a job file from temporary DRAM (the memory supported by all controllers) WARNING: This function is limited to the DRAM root directory.

Parameters:
pathpath of the file to load (pass "" if the root directory is used)
jobname of file to load (may not work with a full path)
Returns:
true if job successfully loaded
static void motoman::controller::Controller::set_bit ( int *  i,
param_func_t  type 
) [inline, static, protected]

Definition at line 438 of file output/controller.h.

static void motoman::controller::Controller::set_bit ( int *  i,
param_func_t  type 
) [inline, static, protected]

Definition at line 438 of file controller.h.

static void motoman::controller::Controller::setCtrlGroup ( int  ctrl_grp) [inline, static]

Definition at line 370 of file output/controller.h.

static void motoman::controller::Controller::setCtrlGroup ( int  ctrl_grp) [inline, static]

Definition at line 370 of file controller.h.

void motoman::controller::Controller::setDigitalOut ( int  bit_offset,
bool  value 
)

Utility function for setting a digital output in the Universal output data table (most IO is accessible there).

Parameters:
bit_offsetbit offset in data table (0-2047)
valuein incoming message

Definition at line 424 of file controller.cpp.

void motoman::controller::Controller::setDigitalOut ( int  bit_offset,
bool  value 
)

Utility function for setting a digital output in the Universal output data table (most IO is accessible there).

Parameters:
bit_offsetbit offset in data table (0-2047)
valuein incoming message
void motoman::controller::Controller::setInteger ( int  index,
int  value 
) [static]

Write integer data to the controller integer data table. Function blocks until data is written.

Parameters:
indexindex in data table
valuevalue to write

Definition at line 113 of file controller.cpp.

static void motoman::controller::Controller::setInteger ( int  index,
int  value 
) [static]

Write integer data to the controller integer data table. Function blocks until data is written.

Parameters:
indexindex in data table
valuevalue to write

Write position-variable data to the controller data table. Function blocks until data is written.

Parameters:
indexindex in data table
ros_jointsjoint positions to write (ROS-order, radians)
Returns:
true if variable set successfully

Write position-variable data to the controller data table. Function blocks until data is written.

Parameters:
indexindex in data table
ros_jointsjoint positions to write (ROS-order, radians)
Returns:
true if variable set successfully

Definition at line 146 of file controller.cpp.

Starts motion job on the controller. Enables motion (Job cannot be started if motion is not enabled).

Definition at line 261 of file controller.cpp.

Starts motion job on the controller. Enables motion (Job cannot be started if motion is not enabled).

Stops motion job on the controller. Disables motion.

Definition at line 284 of file controller.cpp.

Stops motion job on the controller. Disables motion.

void motoman::controller::Controller::waitDigitalIn ( int  bit_offset,
bool  wait_value 
)

Utility function for waiting for a digital input in the Universal input data tabel (most IO is accessible there).

Parameters:
bit_offsetbit offset in data table (0-2047)
wait_valuein incoming message

Definition at line 442 of file controller.cpp.

void motoman::controller::Controller::waitDigitalIn ( int  bit_offset,
bool  wait_value 
)

Utility function for waiting for a digital input in the Universal input data tabel (most IO is accessible there).

Parameters:
bit_offsetbit offset in data table (0-2047)
wait_valuein incoming message
bool motoman::controller::Controller::writeJob ( char *  path,
char *  job 
)

Utility function for writing a job file in temporary DRAM (the memory supported by all controllers)

Parameters:
pathfull path and name of file to create
jobfull job string
Returns:
true if file successfully opened
bool motoman::controller::Controller::writeJob ( char *  path,
char *  job 
)

Utility function for writing a job file in temporary DRAM (the memory supported by all controllers)

Parameters:
pathfull path and name of file to create
jobfull job string
Returns:
true if file successfully opened

Definition at line 303 of file controller.cpp.


Member Data Documentation

static int motoman::controller::Controller::active_ctrl_grp_ = 0 [static, protected]

Definition at line 434 of file controller.h.

MP_HOLD_SEND_DATA motoman::controller::Controller::hold_data [protected]

Definition at line 410 of file controller.h.

MP_STD_RSP_DATA motoman::controller::Controller::hold_error [protected]

Definition at line 411 of file controller.h.

MP_DELETE_JOB_SEND_DATA motoman::controller::Controller::job_delete_data [protected]

Definition at line 405 of file controller.h.

MP_STD_RSP_DATA motoman::controller::Controller::job_error [protected]

Definition at line 406 of file controller.h.

MP_START_JOB_SEND_DATA motoman::controller::Controller::job_start_data [protected]

Definition at line 404 of file controller.h.

True if job started.

Definition at line 423 of file controller.h.

True if motion enabled.

Definition at line 418 of file controller.h.

static const int motoman::controller::Controller::MP_ERROR = -1 [static, protected]

Typical MP function call return on error.

Definition at line 382 of file controller.h.

static const int motoman::controller::Controller::MP_OK = 0 [static, protected]

Typical MP function call return on OK (sometimes a value greater than zero is also returned if it has some meaning, like a file descriptor.

Definition at line 389 of file controller.h.

MP_SERVO_POWER_SEND_DATA motoman::controller::Controller::servo_power_data [protected]

Definition at line 400 of file controller.h.

Definition at line 401 of file controller.h.

static const int motoman::controller::Controller::UNIV_IN_DATA_START_ = 10 [static, protected]

Definition at line 395 of file controller.h.

static const int motoman::controller::Controller::UNIV_IO_DATA_SIZE_ = 2048 [static, protected]

Definition at line 397 of file controller.h.

static const int motoman::controller::Controller::UNIV_OUT_DATA_START_ = 10010 [static, protected]

Definition at line 396 of file controller.h.

static const int motoman::controller::Controller::VAR_POLL_DELAY_ = 10 [static, protected]

Poll delay (in ticks) when querying the motoplus api.

Definition at line 394 of file controller.h.

static const int motoman::controller::Controller::VELOCITY_LIMIT_INDEX = 94 [static, protected]

Index within integer data table that holds velocity limit.

Definition at line 377 of file controller.h.


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


dx100
Author(s): Shaun Edwards (Southwest Research Institute)
autogenerated on Mon Oct 6 2014 02:25:34