Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SetPTPCartesianVelocity returning 1 #281

Open
MonsisGit opened this issue Feb 23, 2022 · 1 comment
Open

SetPTPCartesianVelocity returning 1 #281

MonsisGit opened this issue Feb 23, 2022 · 1 comment

Comments

@MonsisGit
Copy link

MonsisGit commented Feb 23, 2022

Hi everyone,

I am trying to simply control the cartesian velocity with the service "/iiwa/configuration/setPTPCartesianLimits"

Here is my code:
` #include "../include/realtime_pos_control.h"

void set_ptp_cartesian(float max_cart_vel = -1, float max_cart_acc = -1){
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<iiwa_msgs::SetPTPCartesianSpeedLimits>("/iiwa/configuration/setPTPCartesianLimits");
//iiwa_msgs::CartesianControlModeLimits cart_limits;
//iiwa_msgs::CartesianQuantity max_cart_vel

iiwa_msgs::SetPTPCartesianSpeedLimits cart_limits;
cart_limits.request.maxCartesianAcceleration = max_cart_acc;
cart_limits.request.maxCartesianVelocity = max_cart_vel;

if (client.call(cart_limits))
{
ROS_INFO("Set cartesian velocity to: %f returns: %d", max_cart_vel,cart_limits.response.success);
}
else
{
ROS_INFO("Error: %s", cart_limits.response.error.c_str());
}

}

geometry_msgs::PoseStamped set_cartesian_pose(float x, float y, float z, int sequence){

geometry_msgs::PoseStamped commanded_pose;
commanded_pose.pose.position.x = x;
commanded_pose.pose.position.y = y;
commanded_pose.pose.position.z = z;

commanded_pose.pose.orientation.x = 0;
commanded_pose.pose.orientation.y = 0;
commanded_pose.pose.orientation.z = 0;
commanded_pose.pose.orientation.w = 1;

commanded_pose.header.stamp = ros::Time::now();
commanded_pose.header.frame_id = "iiwa_link_0";
commanded_pose.header.seq=sequence;

return commanded_pose;
}

int main(int argc, char **argv)
{

ros::init(argc, argv, "pos_control");
ros::NodeHandle node_handle;
ros::Publisher pose_publisher = node_handle.advertise<geometry_msgs::PoseStamped>("/iiwa/command/CartesianPose",1);
ros::Rate loop_rate(0.2);

ros::Duration(0.5).sleep();
int count = 1;

while(ros::ok()){
geometry_msgs::PoseStamped commanded_pose;
if (count%2==0){
commanded_pose = set_cartesian_pose(0.4,0.1,1,count);
}
else{
commanded_pose = set_cartesian_pose(0.2,-0.4,0.8,count);
}

std::cerr << "Setting new Pose" << std::endl;
ROS_INFO_STREAM(commanded_pose);
set_ptp_cartesian(0.1,0.1);

pose_publisher.publish(commanded_pose);
count ++;
loop_rate.sleep();
ros::spinOnce();

}

return 0;
}`

this is my console output:
[ INFO] [1645623397.611551181]: Set cartesian velocity to: 0.010000 returns: 1 Setting new Pose [ INFO] [1645623397.611674828]: header: seq: 50 stamp: 1645623397.591274955 frame_id: iiwa_link_0 pose: position: x: 0.4 y: 0.1 z: 1 orientation: x: 0 y: 0 z: 0 w: 1

The robot doesn not seem to change velocity for varying values, response.success also returns a 1.
Can somebody help me out please? I also tried the command topics for cartesian velocity and joint velocities without success.

Thank you!

@exo-core
Copy link
Contributor

There are two different control mechanisms in the iiwa: 1) standard point-to-point (PTP) motions where the arm gets a defined target pose and then executes the entire motion and 2) SmartServo motions where the arm awaits continuous way points with around 50Hz. In ROS this is represented by having an ROS action based interface for PTP motion and a purely message based interface for SmartServo motions. Also both motion types have there own speed limit settings.

This being said: In your code you are setting a speed limit for PTP motions and then command the robot to execute a SmartServo motion (which has no speed limit configured).

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants