xArm-Developer / xarm_ros

ROS packages for robotic products from UFACTORY
https://www.ufactory.cc/
BSD 3-Clause "New" or "Revised" License
213 stars 158 forks source link

Open up Joint State Publishing Frequency as a ROS Parameter #55

Open swiz23 opened 3 years ago

swiz23 commented 3 years ago

...instead of having it hardcoded in the xarm_driver_node to 10 as shown at https://github.com/xArm-Developer/xarm_ros/blob/34e42794598c3ac2eefce37cf82767dbc9c85718/xarm_api/src/xarm_driver_node.cpp#L138

That way, it would be easier for me to create a ROS node that does record and playback.

penglongxiang commented 3 years ago

Hi, currently the actual full-state report from xArm controller changes only in 5Hz, we did not make it a ros parameter because there is not much margin for adjustment. You may modify your local code for your convenience. Or if you want a higher feedback rate, check our developer manual, and search for "REPORT_TCP_DEVELOP", that is to connect the controller IP at port 30003, and decode the data for critical joint states reporting at 100Hz.

swiz23 commented 3 years ago

So what's running at 10hz in the code there?

penglongxiang commented 3 years ago

10Hz is the frequency to check the update of xArm full-state report.

JuliusSustarevas commented 3 years ago

Sorry, I'm just evaluating if the arm is suitable for me. Can you tell me what information is inside this report? Does this mean xarm joint-states are being updated only at 5Hz? that seems to be incredibly slow, is there a plan to address this in the future? Presumably the controllers are able to control it much faster, the joint states here are just how fast it publishes to outside the control box? I plan todo disturbance rejection using the arm to stabilise the end-effector. Will the arm be able to be controlled effectively at 50-100Hz?

penglongxiang commented 3 years ago

@JuliusSustarevas For more information about the 5Hz report, please check the developer manual link in my previous answer at page 66 "REPORT_TCP_NORMAL". Inside our controller, the feedback and control rate are 250Hz, however currently in ROS joint_state interface we use a 5Hz automatic state report. User can still get the robot pose through our SDK at max 250Hz, or interpret report channel "REPORT_TCP_DEVELOP"(developer manual page 65) which updates at 100Hz.

Normally our planner in control box will help do trajectory planning to specified target. If you would like to control xArm position in real-time, please refer here for "servo_cartesian" and "servo_joint" interface, which support max command frequency at 250Hz theoretically.

Velocity control will also come soon.

JuliusSustarevas commented 2 years ago

Hi @penglongxiang Could you elaborate a bit what would I need to do to get higher joint state out of the arm? Maybe point to specific lines/files?

Specifically - I use the xarm hardware interface to do joint velocity control. I believe this means the HW interface loads up joint_state_controller (which is actually an observer) that reads and publishes the robot joint states? The joint_state_controller is set to 50Hz. But I guess joints arent internally updated inside the harwdawre interface?

JuliusSustarevas commented 2 years ago

In hardware interface I see line 92 is now commented out: // pos_sub_ = root_nh.subscribe(jnt_state_topic, 100, &XArmHW::pos_fb_cb, this);

Which i guess its good you no longer just republish states that were published using the driver.

I see that read is back and is actually calling read_code_ = xarm.getServoAngle(curr_read_angles_); which in turn just calls a service?!! int ret = _call_service(get_servo_angle_client_, get_float32_list_srv_); Doesnt this lead to VERY BAD latency for feedback ? Rosservices are not meant for high frequency data exchange. Why cant the HW read function just use the xarmapi::xarmdriver get_servo_angle ?

Or even better -> since XArmROSClient is already rossified. best way to do get joint state would be just publish joint states from XArmROSClient using the same commands as it does right now using arm->get_servo_angle

penglongxiang commented 2 years ago

Hi @JuliusSustarevas , we added the read() in hardware interface for better reaction when communication fails. Currently the ros service method did not show quite significant influence yet, and we've set the frequently called services to be persistent service. But indeed, this may not be a good implementation, we will consider to remove the service calling and potential delay, thanks for your kind advice.

JuliusSustarevas commented 2 years ago

Hi but can you confirm that reading directly at say 100hz is ok? Using the getservoangle function? from the driver?

On Fri, Jan 21, 2022 at 8:51 AM penglongxiang @.***> wrote:

Hi @JuliusSustarevas https://github.com/JuliusSustarevas , we added the read() in hardware interface for better reaction when communication fails. Currently the ros service method did not show quite significant influence yet, and we've set the frequently called services to be persistent service. But indeed, this may not be a good implementation, we will consider to remove the service calling and potential delay, thanks for your kind advice.

— Reply to this email directly, view it on GitHub https://github.com/xArm-Developer/xarm_ros/issues/55#issuecomment-1018302436, or unsubscribe https://github.com/notifications/unsubscribe-auth/AH7P7DF7R2D6SAAGEYRJ453UXEM7PANCNFSM4VEZVZBA . Triage notifications on the go with GitHub Mobile for iOS https://apps.apple.com/app/apple-store/id1477376905?ct=notification-email&mt=8&pt=524675 or Android https://play.google.com/store/apps/details?id=com.github.android&referrer=utm_campaign%3Dnotification-email%26utm_medium%3Demail%26utm_source%3Dgithub.

You are receiving this because you were mentioned.Message ID: @.***>

JuliusSustarevas commented 2 years ago

I am using a commit from july 2021 and don't want to update just because everything seems to work so.. no reason to introduce new things :D I just wanna get that joint_states callback. In the commit I'm using joint_states is coming from a report callback. So I plan to just fork and change that to use the getservoangle

On Fri, Jan 21, 2022 at 9:04 AM J S @.***> wrote:

Hi but can you confirm that reading directly at say 100hz is ok? Using the getservoangle function? from the driver?

On Fri, Jan 21, 2022 at 8:51 AM penglongxiang @.***> wrote:

Hi @JuliusSustarevas https://github.com/JuliusSustarevas , we added the read() in hardware interface for better reaction when communication fails. Currently the ros service method did not show quite significant influence yet, and we've set the frequently called services to be persistent service. But indeed, this may not be a good implementation, we will consider to remove the service calling and potential delay, thanks for your kind advice.

— Reply to this email directly, view it on GitHub https://github.com/xArm-Developer/xarm_ros/issues/55#issuecomment-1018302436, or unsubscribe https://github.com/notifications/unsubscribe-auth/AH7P7DF7R2D6SAAGEYRJ453UXEM7PANCNFSM4VEZVZBA . Triage notifications on the go with GitHub Mobile for iOS https://apps.apple.com/app/apple-store/id1477376905?ct=notification-email&mt=8&pt=524675 or Android https://play.google.com/store/apps/details?id=com.github.android&referrer=utm_campaign%3Dnotification-email%26utm_medium%3Demail%26utm_source%3Dgithub.

You are receiving this because you were mentioned.Message ID: @.***>

penglongxiang commented 2 years ago

According to our recent test, reading (by xArmHW) at 100Hz seems to be OK. As long as the network connection is reliable and stable.