Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
thormang3::HeadControlModule Class Reference

#include <head_control_module.h>

Inheritance diagram for thormang3::HeadControlModule:
Inheritance graph
[legend]

Public Member Functions

 HeadControlModule ()
 
void initialize (const int control_cycle_msec, robotis_framework::Robot *robot)
 
bool isRunning ()
 
void process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
 
void stop ()
 
virtual ~HeadControlModule ()
 
- Public Member Functions inherited from robotis_framework::MotionModule
ControlMode getControlMode ()
 
bool getModuleEnable ()
 
std::string getModuleName ()
 
virtual void onModuleDisable ()
 
virtual void onModuleEnable ()
 
void setModuleEnable (bool enable)
 
virtual ~MotionModule ()
 

Private Types

enum  HeadLidarMode {
  None, BeforeStart, StartMove, EndMove,
  AfterMove, ModeCount
}
 

Private Member Functions

void afterMoveLidar ()
 
void beforeMoveLidar (double start_angle)
 
Eigen::MatrixXd calcLinearInterpolationTra (double pos_start, double pos_end, double smp_time, double mov_time)
 
Eigen::MatrixXd calcMinimumJerkTraPVA (double pos_start, double vel_start, double accel_start, double pos_end, double vel_end, double accel_end, double smp_time, double mov_time)
 
void finishMoving ()
 
void get3DLidarCallback (const std_msgs::String::ConstPtr &msg)
 
void get3DLidarRangeCallback (const std_msgs::Float64::ConstPtr &msg)
 
void jointTraGeneThread ()
 
void lidarJointTraGeneThread ()
 
void publishDoneMsg (const std::string done_msg)
 
void publishLidarMoveMsg (std::string msg_data)
 
void publishStatusMsg (unsigned int type, std::string msg)
 
void queueThread ()
 
void setHeadJointCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void setHeadJointTimeCallback (const thormang3_head_control_module_msgs::HeadJointPose::ConstPtr &msg)
 
void startMoveLidar (double target_angle)
 
void startMoving ()
 
void stopMoving ()
 

Private Attributes

Eigen::MatrixXd calc_joint_accel_tra_
 
Eigen::MatrixXd calc_joint_tra_
 
Eigen::MatrixXd calc_joint_vel_tra_
 
int control_cycle_msec_
 
Eigen::MatrixXd current_position_
 
int current_state_
 
const bool DEBUG
 
Eigen::MatrixXd goal_acceleration_
 
Eigen::MatrixXd goal_position_
 
Eigen::MatrixXd goal_velocity_
 
bool is_direct_control_
 
bool is_moving_
 
ros::Publisher movement_done_pub_
 
ros::Publisher moving_head_pub_
 
double moving_time_
 
double original_position_lidar_
 
boost::thread queue_thread_
 
const double SCAN_END_ANGLE = 85 * M_PI / 180
 
double scan_range_
 
const double SCAN_START_ANGLE = -10 * M_PI / 180
 
ros::Publisher status_msg_pub_
 
bool stop_process_
 
Eigen::MatrixXd target_position_
 
int tra_count_
 
boost::thread * tra_gene_thread_
 
boost::mutex tra_lock_
 
int tra_size_
 
std::map< std::string, int > using_joint_name_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< HeadControlModule >
static void destroyInstance ()
 
static T * getInstance ()
 
- Public Attributes inherited from robotis_framework::MotionModule
std::map< std::string, DynamixelState * > result_
 
- Protected Member Functions inherited from robotis_framework::Singleton< HeadControlModule >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::MotionModule
ControlMode control_mode_
 
bool enable_
 
std::string module_name_
 

Detailed Description

Definition at line 45 of file head_control_module.h.

Member Enumeration Documentation

Enumerator
None 
BeforeStart 
StartMove 
EndMove 
AfterMove 
ModeCount 

Definition at line 116 of file head_control_module.h.

Constructor & Destructor Documentation

HeadControlModule::HeadControlModule ( )

Definition at line 29 of file head_control_module.cpp.

HeadControlModule::~HeadControlModule ( )
virtual

Definition at line 61 of file head_control_module.cpp.

Member Function Documentation

void HeadControlModule::afterMoveLidar ( )
private

Definition at line 517 of file head_control_module.cpp.

void HeadControlModule::beforeMoveLidar ( double  start_angle)
private

Definition at line 465 of file head_control_module.cpp.

Eigen::MatrixXd HeadControlModule::calcLinearInterpolationTra ( double  pos_start,
double  pos_end,
double  smp_time,
double  mov_time 
)
private

Definition at line 610 of file head_control_module.cpp.

Eigen::MatrixXd HeadControlModule::calcMinimumJerkTraPVA ( double  pos_start,
double  vel_start,
double  accel_start,
double  pos_end,
double  vel_end,
double  accel_end,
double  smp_time,
double  mov_time 
)
private

Definition at line 563 of file head_control_module.cpp.

void HeadControlModule::finishMoving ( )
private

Definition at line 391 of file head_control_module.cpp.

void HeadControlModule::get3DLidarCallback ( const std_msgs::String::ConstPtr &  msg)
private

Definition at line 103 of file head_control_module.cpp.

void HeadControlModule::get3DLidarRangeCallback ( const std_msgs::Float64::ConstPtr &  msg)
private

Definition at line 131 of file head_control_module.cpp.

void HeadControlModule::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 66 of file head_control_module.cpp.

bool HeadControlModule::isRunning ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 371 of file head_control_module.cpp.

void HeadControlModule::jointTraGeneThread ( )
private

Definition at line 625 of file head_control_module.cpp.

void HeadControlModule::lidarJointTraGeneThread ( )
private

Definition at line 668 of file head_control_module.cpp.

void HeadControlModule::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, double >  sensors 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 292 of file head_control_module.cpp.

void HeadControlModule::publishDoneMsg ( const std::string  done_msg)
private

Definition at line 714 of file head_control_module.cpp.

void HeadControlModule::publishLidarMoveMsg ( std::string  msg_data)
private

Definition at line 537 of file head_control_module.cpp.

void HeadControlModule::publishStatusMsg ( unsigned int  type,
std::string  msg 
)
private

Definition at line 703 of file head_control_module.cpp.

void HeadControlModule::queueThread ( )
private

Definition at line 81 of file head_control_module.cpp.

void HeadControlModule::setHeadJointCallback ( const sensor_msgs::JointState::ConstPtr &  msg)
private

Definition at line 160 of file head_control_module.cpp.

void HeadControlModule::setHeadJointTimeCallback ( const thormang3_head_control_module_msgs::HeadJointPose::ConstPtr &  msg)
private

Definition at line 226 of file head_control_module.cpp.

void HeadControlModule::startMoveLidar ( double  target_angle)
private

Definition at line 491 of file head_control_module.cpp.

void HeadControlModule::startMoving ( )
private

Definition at line 376 of file head_control_module.cpp.

void HeadControlModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 359 of file head_control_module.cpp.

void HeadControlModule::stopMoving ( )
private

Definition at line 440 of file head_control_module.cpp.

Member Data Documentation

Eigen::MatrixXd thormang3::HeadControlModule::calc_joint_accel_tra_
private

Definition at line 112 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::calc_joint_tra_
private

Definition at line 110 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::calc_joint_vel_tra_
private

Definition at line 111 of file head_control_module.h.

int thormang3::HeadControlModule::control_cycle_msec_
private

Definition at line 88 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::current_position_
private

Definition at line 106 of file head_control_module.h.

int thormang3::HeadControlModule::current_state_
private

Definition at line 101 of file head_control_module.h.

const bool thormang3::HeadControlModule::DEBUG
private

Definition at line 95 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::goal_acceleration_
private

Definition at line 109 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::goal_position_
private

Definition at line 107 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::goal_velocity_
private

Definition at line 108 of file head_control_module.h.

bool thormang3::HeadControlModule::is_direct_control_
private

Definition at line 98 of file head_control_module.h.

bool thormang3::HeadControlModule::is_moving_
private

Definition at line 97 of file head_control_module.h.

ros::Publisher thormang3::HeadControlModule::movement_done_pub_
private

Definition at line 94 of file head_control_module.h.

ros::Publisher thormang3::HeadControlModule::moving_head_pub_
private

Definition at line 92 of file head_control_module.h.

double thormang3::HeadControlModule::moving_time_
private

Definition at line 100 of file head_control_module.h.

double thormang3::HeadControlModule::original_position_lidar_
private

Definition at line 102 of file head_control_module.h.

boost::thread thormang3::HeadControlModule::queue_thread_
private

Definition at line 89 of file head_control_module.h.

const double thormang3::HeadControlModule::SCAN_END_ANGLE = 85 * M_PI / 180
private

Definition at line 59 of file head_control_module.h.

double thormang3::HeadControlModule::scan_range_
private

Definition at line 103 of file head_control_module.h.

const double thormang3::HeadControlModule::SCAN_START_ANGLE = -10 * M_PI / 180
private

Definition at line 58 of file head_control_module.h.

ros::Publisher thormang3::HeadControlModule::status_msg_pub_
private

Definition at line 93 of file head_control_module.h.

bool thormang3::HeadControlModule::stop_process_
private

Definition at line 96 of file head_control_module.h.

Eigen::MatrixXd thormang3::HeadControlModule::target_position_
private

Definition at line 105 of file head_control_module.h.

int thormang3::HeadControlModule::tra_count_
private

Definition at line 99 of file head_control_module.h.

boost::thread* thormang3::HeadControlModule::tra_gene_thread_
private

Definition at line 90 of file head_control_module.h.

boost::mutex thormang3::HeadControlModule::tra_lock_
private

Definition at line 91 of file head_control_module.h.

int thormang3::HeadControlModule::tra_size_
private

Definition at line 99 of file head_control_module.h.

std::map<std::string, int> thormang3::HeadControlModule::using_joint_name_
private

Definition at line 114 of file head_control_module.h.


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


thormang3_head_control_module
Author(s): Zerom , SCH , Kayman
autogenerated on Mon Jun 10 2019 15:37:48