smooth movement of the gripper

This commit is contained in:
NikoFeith 2024-05-15 13:28:36 +02:00
parent 1ffa81cfba
commit b765cba632
3 changed files with 53 additions and 2 deletions

View File

@ -0,0 +1,51 @@
#!/bin/bash
# Create a Tilix layout file in JSON format
layout_file=$(mktemp)
cat <<EOL > $layout_file
{
"type": "Window",
"tabs": [
{
"type": "Terminal",
"children": [
{
"type": "Terminal",
"children": [
{
"type": "Terminal",
"command": "bash -c 'cd ~/PycharmProjects/UR_Robotiq && . install/setup.bash; exec bash'"
},
{
"type": "Terminal",
"command": "bash -c 'cd ~/PycharmProjects/UR_Robotiq && . install/setup.bash; exec bash'"
}
],
"orientation": "vertical"
},
{
"type": "Terminal",
"children": [
{
"type": "Terminal",
"command": "bash -c 'cd ~/PycharmProjects/UR_Robotiq && . install/setup.bash; exec bash'"
},
{
"type": "Terminal",
"command": "bash -c 'cd ~/PycharmProjects/UR_Robotiq && . install/setup.bash; exec bash'"
}
],
"orientation": "vertical"
}
],
"orientation": "horizontal"
}
]
}
EOL
# Open Tilix with the specified layout
tilix --session $layout_file
# Remove the temporary layout file
rm $layout_file

View File

@ -8,7 +8,7 @@ command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joy
scale:
# Scale parameters are only used if command_in_type=="unitless"
linear: 0.4 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
rotational: 0.8 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
rotational: 3.2 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
# Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic.
joint: 0.5
# This is a fudge factor to account for any latency in the system, e.g. network latency or poor low-level

View File

@ -159,7 +159,7 @@ class PS5ControllerNode(Node):
twist_msg.header.frame_id = 'tool0'
twist_msg.header.stamp = self.get_clock().now().to_msg()
twist_msg.twist.linear.x = msg.axes[self.mappings['axes']['LeftStickHorizontal']] * self.linear_speed_multiplier
twist_msg.twist.linear.y = -msg.axes[self.mappings['axes']['LeftStickVertical']] * self.linear_speed_multiplier
twist_msg.twist.linear.y = msg.axes[self.mappings['axes']['LeftStickVertical']] * self.linear_speed_multiplier
twist_msg.twist.linear.z = (left_trigger - right_trigger) * self.linear_speed_multiplier
twist_msg.twist.angular.x = msg.axes[self.mappings['axes']['RightStickHorizontal']]
twist_msg.twist.angular.y = msg.axes[self.mappings['axes']['RightStickVertical']]