CDRFLEx.servoj_rt
Features
This is a function that controls the joint position from an external controller.
Caution
- The current servoj_rt command is premature. Jerky motion may appear depending on the communication situation, so it is recommended to tune the target time (fTargetTime) and use it with a slow response speed, or use the speedj_rt command to control the position.
Parameter
Parameter Name | Data Type | Default Value | Description |
fTargetPos | float[6] | - | Target Joint Position [deg] |
fTargetVel | float[6] | - | Target Joint Velocity [deg/s]. If None Values(-10000) entered, it is automatically calculated based on the target joint position you entered. |
fTargetAcc | float[6] | - | Target Joint Acceleration [deg/s2]. If None Values(-10000) entered, it is automatically calculated based on the target joint position you entered. |
fTargetTime | float | - | Target Time [s] |
Note
- Asnyc command.
- The inner profile is interpolated to arrive at (fTargetPos, fTargetVel, fTargetAcc) at fTargetTime .
- If fTargetTime <= controller’s control period (=1ms) is entered, it controls to the corresponding position without interpolation.
- If the next command is not received until arriving at fTargetPos, it decelerates based on the set global acceleration value.
Caution
- The current servoj_rt command is premature, so jerky motion may come out. Depending on the system situation, set fTargetTime to be larger than the communication period and use it. In the current version, it is recommended to use a setting larger than fTargetTime >= 20 [ms] or use speedj_rt to control the position based on calling the servoj_rt command at an interval of 1 [ms].
- In the current version, it is not linked with Operation Speed [%].
Return
Value | Description |
0 | Error |
1 | Success |
Example
// main.cpp
CDRFLEx drfl;
drfl.connect_rt_control();
string version = “v1.0”;
float period = 0.001; // 1 msec
int losscount = 4;
Drfl.set_on_rt_monitoring_data(OnRTMonitoringData);
drfl.set_rt_control_output(version, period, losscount);
drfl.start_rt_control();
float time = 0.0;
int count = 0;
float ratio = 20.0;
float q[NUMBER_OF_JOINT] = {0.0, };
float q_dot[NUMBER_OF_JOINT] = {0.0, };
float q_d[NUMBER_OF_JOINT] = {0.0, };
float q_dot_d[NUMBER_OF_JOINT] = {0.0, };
float integral_v_error[NUMBER_OF_JOINT] = {0.0, };
while (1)
{
time=(++count)*period;
// get current state
memcpy(q, drfl.read_data_rt()->actual_joint_position, sizeof(float)*6);
memcpy(q_dot, drfl.read_data_rt()->actual_joint_velocity, sizeof(float)*6);
// make trajectory
TrajectoryGenerator(q_d, q_dot_d, q_ddot_d); // Custom Trajectory Generation Function
// or make target position and target velocity, acceleration can be omitted
TrajectoryGenerator(q_d);
for (int i=0; i<NUMBER_OF_JOINT; i++) {
q_dot_d[i] = -10000;
q_ddot_d[i] = -10000;
}
drfl.servoj_rt(q_d, q_dot_d, q_ddot_d, ratio*period); // Currently tuning ratio
if(time > plan1.time)
{
time=0;
Drfl.stop(STOP_TYPE_SLOW);
break;
}
rt_task_wait_period(NULL); // RTOS function
}