Public Member Functions | Protected Member Functions | Protected Attributes
IxisImcs01Driver Class Reference

#include <ixis_imcs01_driver.h>

List of all members.

Public Member Functions

int controlRearWheel (double rear_speed)
sensor_msgs::JointState getJointState ()
 IxisImcs01Driver (std::string port_name)
int update ()
 ~IxisImcs01Driver ()

Protected Member Functions

int closePort ()
int openPort (std::string port_name)
int parseEncoderTime ()
int parseFrontEncoderCounts ()
int parseRearEncoderCounts ()
int setImcs01 ()
int writeOffsetCmd (RunningMode mode, unsigned short duty)

Protected Attributes

struct ccmd cmd_ccmd_
struct uin cmd_uin_
std::mutex communication_mutex_
double delta_encoder_time_
int imcs01_fd_
double last_encoder_time_
termios newtio_imcs01_
termios oldtio_imcs01_
std::vector< int > rear_delta_encoder_counts_
std::vector< int > rear_last_encoder_counts_
struct uin received_data_
RunningState running_state_
sensor_msgs::JointState state_

Detailed Description

Definition at line 52 of file ixis_imcs01_driver.h.


Constructor & Destructor Documentation

IxisImcs01Driver::IxisImcs01Driver ( std::string  port_name)

Definition at line 15 of file ixis_imcs01_driver.cpp.

Definition at line 37 of file ixis_imcs01_driver.cpp.


Member Function Documentation

int IxisImcs01Driver::closePort ( ) [protected]

if iMCs01 is opened

Definition at line 54 of file ixis_imcs01_driver.cpp.

int IxisImcs01Driver::controlRearWheel ( double  rear_speed)

Definition at line 180 of file ixis_imcs01_driver.cpp.

sensor_msgs::JointState IxisImcs01Driver::getJointState ( )

Definition at line 175 of file ixis_imcs01_driver.cpp.

int IxisImcs01Driver::openPort ( std::string  port_name) [protected]

Definition at line 42 of file ixis_imcs01_driver.cpp.

Definition at line 122 of file ixis_imcs01_driver.cpp.

Definition at line 134 of file ixis_imcs01_driver.cpp.

Definition at line 142 of file ixis_imcs01_driver.cpp.

int IxisImcs01Driver::setImcs01 ( ) [protected]

Definition at line 68 of file ixis_imcs01_driver.cpp.

Definition at line 107 of file ixis_imcs01_driver.cpp.

int IxisImcs01Driver::writeOffsetCmd ( RunningMode  mode,
unsigned short  duty 
) [protected]

Definition at line 264 of file ixis_imcs01_driver.cpp.


Member Data Documentation

struct ccmd IxisImcs01Driver::cmd_ccmd_ [protected]

Definition at line 77 of file ixis_imcs01_driver.h.

struct uin IxisImcs01Driver::cmd_uin_ [protected]

Definition at line 78 of file ixis_imcs01_driver.h.

Definition at line 81 of file ixis_imcs01_driver.h.

Definition at line 72 of file ixis_imcs01_driver.h.

Definition at line 75 of file ixis_imcs01_driver.h.

Definition at line 73 of file ixis_imcs01_driver.h.

termios IxisImcs01Driver::newtio_imcs01_ [protected]

Definition at line 80 of file ixis_imcs01_driver.h.

termios IxisImcs01Driver::oldtio_imcs01_ [protected]

Definition at line 79 of file ixis_imcs01_driver.h.

std::vector<int> IxisImcs01Driver::rear_delta_encoder_counts_ [protected]

Definition at line 71 of file ixis_imcs01_driver.h.

std::vector<int> IxisImcs01Driver::rear_last_encoder_counts_ [protected]

Definition at line 70 of file ixis_imcs01_driver.h.

Definition at line 69 of file ixis_imcs01_driver.h.

Definition at line 76 of file ixis_imcs01_driver.h.

sensor_msgs::JointState IxisImcs01Driver::state_ [protected]

Definition at line 74 of file ixis_imcs01_driver.h.


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


cirkit_unit03_base
Author(s): CIR-KIT
autogenerated on Thu Jun 6 2019 21:08:13