Closed benthebear93 closed 3 years ago
It could be it's a bug in the VAL 3 code, we don't know right now.
As in https://github.com/ros-industrial/staubli_val3_driver/issues/25#issuecomment-737170702, please provide:
Please provide the following:
a full copy-paste of the output on your console after
roslaunch
ing your system (append--screen
to theroslaunch
command so all the output is shown)ideally some code which shows how you generate your trajectories, and how you submit them to the driver (note: we don't need a full application. Just the segment(s) which is (are) responsible for putting together the actual trajectory and the goal)
the ROS
JointTrajectory
which gets submitted as part of the action goal to the drivera capture of the network traffic between the ROS pc and the CS9
The trajectory you should be able to capture using
rostopic echo
on the topic which carries the goal message.Network traffic can be captured using Wireshark.
I will try to provide all information asap
1. Here is full copy-pase of output console of roslaunch
2. Here is the some code that i used to generation trajectory (moveit client with python)
def plan_cartesian_path(self, scale=1):
print ("plan cartersian")
group = self.move_group
waypoints = []
wpose = group.get_current_pose().pose
for i in range(15):
wpose.position.z -= scale * 0.05
waypoints.append(copy.deepcopy(wpose))
print("waypoints ", waypoints[i])
for i in range(15):
wpose.position.x += scale * 0.1
waypoints.append(copy.deepcopy(wpose))
print("waypoints ", waypoints[i])
for i in range(15):
wpose.position.y += scale * 0.1
waypoints.append(copy.deepcopy(wpose))
print("waypoints ", waypoints[i])
# We want the Cartesian path to be interpolated at a resolution of 1 cm
# which is why we will specify 0.01 as the eef_step in Cartesian
# translation. We will disable the jump threshold by setting it to 0.0 disabling:
(plan, fraction) = group.compute_cartesian_path(
waypoints, # waypoints to follow
0.01, # eef_step
0.0) # jump_threshold
# Note: We are just planning, not asking move_group to actually move the robot yet:
return plan, fraction
def execute_plan(self, plan):
self.move_group.execute(plan, wait=True)
if __name__ == '__main__':
staubli_client = StaubliScanning()
cartesian_plan, fraction = staubli_client.plan_cartesian_path()
staubli_client.execute_plan(cartesian_plan)
3. Here is JointTrajectory echo. (not sure this is what you want it)
I will try to fill more information about network traffic, since i never used Wireshark, with roslaunch log and JointTrajectory echo data again, (probably tomorrow).
Thx for the help!
1. Here is full copy-pase of output console of roslaunch
2. Here is the some code that i used to generation trajectory (moveit client with python)
def plan_cartesian_path(self, scale=1):
print ("plan cartersian")
group = self.move_group
waypoints = []
wpose = group.get_current_pose().pose
for i in range(7):
wpose.position.z -= scale * 0.1
waypoints.append(copy.deepcopy(wpose))
print("waypoints ", waypoints[i])
for i in range(7):
wpose.position.x += scale * 0.1
waypoints.append(copy.deepcopy(wpose))
print("waypoints ", waypoints[i])
# We want the Cartesian path to be interpolated at a resolution of 1 cm
# which is why we will specify 0.01 as the eef_step in Cartesian
# translation. We will disable the jump threshold by setting it to 0.0 disabling:
(plan, fraction) = group.compute_cartesian_path(
waypoints, # waypoints to follow
0.01, # eef_step
0.0) # jump_threshold
# Note: We are just planning, not asking move_group to actually move the robot yet:
return plan, fraction
def execute_plan(self, plan):
self.move_group.execute(plan, wait=True)
if __name__ == '__main__':
staubli_client = StaubliScanning()
cartesian_plan, fraction = staubli_client.plan_cartesian_path()
staubli_client.execute_plan(cartesian_plan)
3. Here is JointTrajectory echo. (not sure this is what you want it)
4. Wireshark log wireshark_log.zip
I got the Wireshark network traffic log.
According to the SimpleMessage traffic (in your wireshark capture), the robot never enabled the drives, nor was it taken out of MANUAL
mode:
ROS-Industrial SimpleMessage, Status (0x0d), 44 bytes, little-endian
Prefix
Packet Length: 40
Header
Message Type: Status (0x0000000d)
Communications Type: Topic (1)
Reply Code: Unused / Invalid (0)
Body
Drives Powered : False (0)
E-Stopped : False (0)
Error Code : 0
In Error : False (0)
In Motion : False (0)
Mode : Manual (1)
Motion Possible: False (0)
Notice how Motion Possible
is False
, and Drives Powered
is also False
.
That would make motion impossible.
Two things:
MANUAL
mode, you cannot let go of the teach pendant. Please refer to the Staubli documentation on how to run programs in manual modeFollowJointTrajectory
goal when the robot does not report it's capable of executing motionAs I don't believe there is a problem right now with staubli_val3_driver
, I'm closing this issue.
If it turns out there is a problem, we can re-open.
@gavanderhoorn
Sorry for bad issue. Yes it was MANUAL
mode problem. changing mode solved problem
thx for the help!
No problem.
Note: running your program(s) in manual mode is not a problem necessarily.
The problem is not holding the teach pendant (depressing the deadman switch, etc).
That will make the robot controller disable the drives.
Hello (env : 18.04, melodic, Tx90)
i been using this pkg to send trajectory to TX90. Every thing seems fine till i tried to send long trajectory. robot_interface_streaming log shows that all the points are sent to controller, but my pendant only got few of the points
here is roslaunch --screen log.
Click to expand
``` [ INFO] [1629529937.060229013]: Using joint names from URDF: 'robot_description': [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6] [ INFO] [1629529937.060520612]: Filtered joint names to 6 joints [ INFO] [1629529937.082788623]: Unlocking mutex [ INFO] [1629529937.082877382]: Starting joint trajectory streamer thread [ INFO] [1629529937.088098549]: Connecting to robot motion server [ WARN] [1629529937.088168345]: Tried to connect when socket already in connected state [ WARN] [1629529938.083812518]: Trajectory state not received for 1.000000 seconds [ INFO] [1629529959.361065248]: Received new goal [ INFO] [1629529959.361299378]: Publishing trajectory [ INFO] [1629529959.362446511]: Receiving joint trajectory message [ WARN] [1629529959.363097194]: Joint velocity-limits unspecified. Using default velocity-ratio. [ INFO] [1629529959.366991150]: Loading trajectory, setting state to streaming [ INFO] [1629529959.367063829]: Executing trajectory of size: 122 [ INFO] [1629529959.380736553]: Point[1 of 122] sent to controller [ INFO] [1629529959.380896108]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.395165687]: Point[2 of 122] sent to controller [ INFO] [1629529959.399821465]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.411128088]: Point[3 of 122] sent to controller [ INFO] [1629529959.419703071]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.427121521]: Point[4 of 122] sent to controller [ INFO] [1629529959.443115726]: Point[5 of 122] sent to controller [ INFO] [1629529959.445508169]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.460490154]: Point[6 of 122] sent to controller [ INFO] [1629529959.460756840]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.475086737]: Point[7 of 122] sent to controller [ INFO] [1629529959.479579891]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.491057778]: Point[8 of 122] sent to controller [ INFO] [1629529959.499626569]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.507063767]: Point[9 of 122] sent to controller [ INFO] [1629529959.523044818]: Point[10 of 122] sent to controller [ INFO] [1629529959.525322925]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.540103078]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.541540422]: Point[11 of 122] sent to controller [ INFO] [1629529959.560087773]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.560406430]: Point[12 of 122] sent to controller [ INFO] [1629529959.575107509]: Point[13 of 122] sent to controller [ INFO] [1629529959.579596198]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.591062971]: Point[14 of 122] sent to controller [ INFO] [1629529959.599562494]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.607095441]: Point[15 of 122] sent to controller [ INFO] [1629529959.623256708]: Point[16 of 122] sent to controller [ INFO] [1629529959.625323065]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.640665806]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.641507269]: Point[17 of 122] sent to controller [ INFO] [1629529959.660506384]: Point[18 of 122] sent to controller [ INFO] [1629529959.660890278]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.674982773]: Point[19 of 122] sent to controller [ INFO] [1629529959.679675191]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.691013872]: Point[20 of 122] sent to controller [ INFO] [1629529959.699563661]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.707057697]: Point[21 of 122] sent to controller [ INFO] [1629529959.719614525]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.724507525]: Point[22 of 122] sent to controller [ INFO] [1629529959.740673843]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.741521878]: Point[23 of 122] sent to controller [ INFO] [1629529959.754961963]: Point[24 of 122] sent to controller [ INFO] [1629529959.759517107]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.770913574]: Point[25 of 122] sent to controller [ INFO] [1629529959.779459494]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.787030686]: Point[26 of 122] sent to controller [ INFO] [1629529959.803007862]: Point[27 of 122] sent to controller [ INFO] [1629529959.804920930]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.820417004]: Point[28 of 122] sent to controller [ INFO] [1629529959.820695461]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.834930857]: Point[29 of 122] sent to controller [ INFO] [1629529959.839476135]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.850903253]: Point[30 of 122] sent to controller [ INFO] [1629529959.859535203]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.866892625]: Point[31 of 122] sent to controller [ INFO] [1629529959.882888908]: Point[32 of 122] sent to controller [ INFO] [1629529959.884872128]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.899896163]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.900315527]: Point[33 of 122] sent to controller [ INFO] [1629529959.914874236]: Point[34 of 122] sent to controller [ INFO] [1629529959.919517101]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.930964196]: Point[35 of 122] sent to controller [ INFO] [1629529959.939428830]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.947085535]: Point[36 of 122] sent to controller [ INFO] [1629529959.959499668]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.964319599]: Point[37 of 122] sent to controller [ INFO] [1629529959.979963202]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529959.980271966]: Point[38 of 122] sent to controller [ INFO] [1629529959.994876909]: Point[39 of 122] sent to controller [ INFO] [1629529959.999333798]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.010844403]: Point[40 of 122] sent to controller [ INFO] [1629529960.019609264]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.026842483]: Point[41 of 122] sent to controller [ INFO] [1629529960.042849534]: Point[42 of 122] sent to controller [ INFO] [1629529960.044968702]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.060276993]: Point[43 of 122] sent to controller [ INFO] [1629529960.060598225]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.074970617]: Point[44 of 122] sent to controller [ INFO] [1629529960.079250956]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.090801053]: Point[45 of 122] sent to controller [ INFO] [1629529960.099310679]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.106810448]: Point[46 of 122] sent to controller [ INFO] [1629529960.122841299]: Point[47 of 122] sent to controller [ INFO] [1629529960.124727542]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.140476718]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.141295269]: Point[48 of 122] sent to controller [ INFO] [1629529960.154789161]: Point[49 of 122] sent to controller [ INFO] [1629529960.159391391]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.170869275]: Point[50 of 122] sent to controller [ INFO] [1629529960.179573194]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.186859992]: Point[51 of 122] sent to controller [ INFO] [1629529960.202800569]: Point[52 of 122] sent to controller [ INFO] [1629529960.204797541]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.220179089]: Point[53 of 122] sent to controller [ INFO] [1629529960.220479533]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.234810772]: Point[54 of 122] sent to controller [ INFO] [1629529960.239366965]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.250966915]: Point[55 of 122] sent to controller [ INFO] [1629529960.259342848]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.266770630]: Point[56 of 122] sent to controller [ INFO] [1629529960.282758396]: Point[57 of 122] sent to controller [ INFO] [1629529960.284724645]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.300326757]: Point[58 of 122] sent to controller [ INFO] [1629529960.300633371]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.314733099]: Point[59 of 122] sent to controller [ INFO] [1629529960.319270076]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.330714042]: Point[60 of 122] sent to controller [ INFO] [1629529960.339364390]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.346759313]: Point[61 of 122] sent to controller [ INFO] [1629529960.359094058]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.364101691]: Point[62 of 122] sent to controller [ INFO] [1629529960.379825099]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.380107355]: Point[63 of 122] sent to controller [ INFO] [1629529960.394726730]: Point[64 of 122] sent to controller [ INFO] [1629529960.399188960]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.410744158]: Point[65 of 122] sent to controller [ INFO] [1629529960.419310498]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.426708227]: Point[66 of 122] sent to controller [ INFO] [1629529960.442673991]: Point[67 of 122] sent to controller [ INFO] [1629529960.444597995]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.460127747]: Point[68 of 122] sent to controller [ INFO] [1629529960.460658445]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.474634560]: Point[69 of 122] sent to controller [ INFO] [1629529960.479427817]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.490685593]: Point[70 of 122] sent to controller [ INFO] [1629529960.499213467]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.506604371]: Point[71 of 122] sent to controller [ INFO] [1629529960.519184358]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.524130768]: Point[72 of 122] sent to controller [ INFO] [1629529960.540454063]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.541141175]: Point[73 of 122] sent to controller [ INFO] [1629529960.559702849]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.560044404]: Point[74 of 122] sent to controller [ INFO] [1629529960.574640098]: Point[75 of 122] sent to controller [ INFO] [1629529960.579273749]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.590724993]: Point[76 of 122] sent to controller [ INFO] [1629529960.599259720]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.606628535]: Point[77 of 122] sent to controller [ INFO] [1629529960.622631374]: Point[78 of 122] sent to controller [ INFO] [1629529960.624645412]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.640252369]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.641006275]: Point[79 of 122] sent to controller [ INFO] [1629529960.654782477]: Point[80 of 122] sent to controller [ INFO] [1629529960.659359182]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.670610608]: Point[81 of 122] sent to controller [ INFO] [1629529960.679183940]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.686587932]: Point[82 of 122] sent to controller [ INFO] [1629529960.699021275]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.703951302]: Point[83 of 122] sent to controller [ INFO] [1629529960.719689545]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.719982925]: Point[84 of 122] sent to controller [ INFO] [1629529960.734572398]: Point[85 of 122] sent to controller [ INFO] [1629529960.739163581]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.750574680]: Point[86 of 122] sent to controller [ INFO] [1629529960.759201494]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.766667597]: Point[87 of 122] sent to controller [ INFO] [1629529960.782558049]: Point[88 of 122] sent to controller [ INFO] [1629529960.784848711]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.799987012]: Point[89 of 122] sent to controller [ INFO] [1629529960.800171291]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.814492946]: Point[90 of 122] sent to controller [ INFO] [1629529960.819178703]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.830512697]: Point[91 of 122] sent to controller [ INFO] [1629529960.839142378]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.846586064]: Point[92 of 122] sent to controller [ INFO] [1629529960.862480765]: Point[93 of 122] sent to controller [ INFO] [1629529960.864525576]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.879559776]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.879837886]: Point[94 of 122] sent to controller [ INFO] [1629529960.894508862]: Point[95 of 122] sent to controller [ INFO] [1629529960.898989272]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.910482450]: Point[96 of 122] sent to controller [ INFO] [1629529960.919258753]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.926472723]: Point[97 of 122] sent to controller [ INFO] [1629529960.942477629]: Point[98 of 122] sent to controller [ INFO] [1629529960.944568131]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.959920698]: Point[99 of 122] sent to controller [ INFO] [1629529960.960363237]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.974478958]: Point[100 of 122] sent to controller [ INFO] [1629529960.979063065]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529960.990609251]: Point[101 of 122] sent to controller [ INFO] [1629529960.999052442]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.006456037]: Point[102 of 122] sent to controller [ INFO] [1629529961.022460680]: Point[103 of 122] sent to controller [ INFO] [1629529961.024421462]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.039462369]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.040847354]: Point[104 of 122] sent to controller [ INFO] [1629529961.054446647]: Point[105 of 122] sent to controller [ INFO] [1629529961.059546536]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.070423398]: Point[106 of 122] sent to controller [ INFO] [1629529961.079184162]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.086482756]: Point[107 of 122] sent to controller [ INFO] [1629529961.102437166]: Point[108 of 122] sent to controller [ INFO] [1629529961.104526757]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.119937247]: Point[109 of 122] sent to controller [ INFO] [1629529961.120216780]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.134383004]: Point[110 of 122] sent to controller [ INFO] [1629529961.139078507]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.150423913]: Point[111 of 122] sent to controller [ INFO] [1629529961.158981683]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.166390762]: Point[112 of 122] sent to controller [ INFO] [1629529961.178930945]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.183808351]: Point[113 of 122] sent to controller [ INFO] [1629529961.199523047]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.199868984]: Point[114 of 122] sent to controller [ INFO] [1629529961.214427122]: Point[115 of 122] sent to controller [ INFO] [1629529961.218834133]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.230555407]: Point[116 of 122] sent to controller [ INFO] [1629529961.239031554]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.246605731]: Point[117 of 122] sent to controller [ INFO] [1629529961.262387161]: Point[118 of 122] sent to controller [ INFO] [1629529961.264414936]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.279560052]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.279771324]: Point[119 of 122] sent to controller [ INFO] [1629529961.294353004]: Point[120 of 122] sent to controller [ INFO] [1629529961.298719989]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.310354603]: Point[121 of 122] sent to controller [ INFO] [1629529961.318956515]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.326301237]: Point[122 of 122] sent to controller [ INFO] [1629529961.331533733]: Trajectory streaming complete, setting state to IDLE [ INFO] [1629529961.338989305]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.358951248]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.378899899]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.398910445]: Waiting to check for goal completion until halfway through trajectory [ INFO] [1629529961.418926000]: Waiting to check for goal completion until halfway through trajectory ```122 points are sent to controller but my pendant only shows 31. Trajectory buffer : 10 21 Motion buffer : 21 0
This seems similar to #25. but little different since my pendant only shows maximum 31. could it be the val3 driver problem ? or is there any setting in the pendant that i don't know about?
Thank you for your help, if more information needed let me know!