RobotControl_7Axis
Dependents: RoboticArm DXL_SDK_Porting_Test
Diff: RobotControl_7Axis.h
- Revision:
- 3:e380c7db9133
- Parent:
- 2:71ed7da9ea36
--- a/RobotControl_7Axis.h Sat Feb 11 13:06:49 2017 +0000 +++ b/RobotControl_7Axis.h Fri Mar 31 16:31:30 2017 +0800 @@ -156,6 +156,28 @@ AXIS6_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_RAD, AXIS7_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_RAD }; + +static const float grobot_lim_pus_L[MAX_AXIS_NUM]= +{ + AXIS1_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS2_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS3_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS4_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS5_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS6_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS, + AXIS7_ROBOT_LIM_DEG_L*DEF_RATIO_DEG_TO_PUS +}; + +static const float grobot_lim_pus_H[MAX_AXIS_NUM]= +{ + AXIS1_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS2_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS3_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS4_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS5_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS6_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS, + AXIS7_ROBOT_LIM_DEG_H*DEF_RATIO_DEG_TO_PUS +}; //================================= //==morot max pulse in joint mode //================================= @@ -182,6 +204,7 @@ int ROM_Setting(); int Read_pos(float *pos,unsigned char unit); int Output_to_Dynamixel(const float *Ang_rad,const unsigned short int *velocity) ; +int Output_to_Dynamixel_pulse(const unsigned short int *Ang_pus,const unsigned short int *velocity); Matrix R_z1x2y3(float alpha,float beta,float gamma); float norm(const Matrix& v); Matrix Rogridues(float theta,const Matrix& V_A);