Roboteq-Inc / ROS-Driver

33 stars 39 forks source link

wrong claculations at roboteq_motor_controller_driver_node.cpp #9

Open noam7777 opened 4 years ago

noam7777 commented 4 years ago

there is a wrong calculation of the command to the motors. what you have now:

void Driver::cmd_vel_callback(const geometry_msgs::Twist& msg){ std::stringstream cmd_sub; cmdsub << "!G 1" << " " << msg.linear.x << "" << "!G 2" << " " << msg.angular.z << "_";

    ser.write(cmd_sub.str());
ROS_INFO_STREAM(cmd_sub.str()); 

} void Driver::roboteq_subscriber(){ ros::NodeHandle n; cmd_vel_sub = n.subscribe("/cmd_vel",10,&Driver::cmd_vel_callback,this);

}

void Driver::roboteq_subscriber(){ ros::NodeHandle n; cmd_vel_sub = n.subscribe("/cmd_vel",10,&Driver::cmd_vel_callback,this);

}

and what you need is void Driver::cmd_vel_callback(const geometry_msgs::Twist& msg){ std::stringstream cmd_sub; double cmd_left, cmd_right; int kW = 1; //TODO:gemotrical property of the robot(width,radius) cmd_left = msg.linear.x-msg.angular.zkW; cmd_right = msg.linear.x+msg.angular.zkW; cmd_sub << "!G 1" << " " << cmdleft << "" << "!G 2" << " " << cmdright << "";

    ser.write(cmd_sub.str());
ROS_INFO_STREAM(cmd_sub.str()); 

} void Driver::roboteq_subscriber(){ ros::NodeHandle n; cmd_vel_sub = n.subscribe("/cmd_vel",10,&Driver::cmd_vel_callback,this);

}

this is a more logical way to calculate the angular velocity to the wheels then before

zhughesjd commented 3 years ago

@noam7777 After reading:

http://wiki.ros.org/simple_drive#Twist_to_Tank_Calculation

I found that the code below did the trick for skid steer type vehicles.

void Driver::cmd_vel_callback(const geometry_msgs::Twist& msg) { std::stringstream cmd_sub; double cmd_left, cmd_right; cmd_left = msg.linear.x-msg.angular.z; cmd_right = msg.linear.x+msg.angular.z; cmd_sub << "!G 1" << " " << cmdleft << "\" << "!G 2" << " " << cmdright << "\"; ser.write(cmd_sub.str()); ROS_INFO_STREAM(cmd_sub.str()); }