The URDF file
<?xml version="1.0"?>
<robot name="one_DOF_robot">
<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="world"/>
<joint name="glue_robot_to_world" type="fixed">
<parent link="world"/>
<child link="link1"/>
</joint>
<!-- Base Link -->
<link name="link1">
<collision>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.2 0.7"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.2 1"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<!-- Moveable Link -->
<link name="link2">
<collision>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="0.1"/>
<!--box size="0.15 0.15 0.8"-->
</geometry>
</collision>
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="0.1"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="0.1" ixy="0.0" ixz="0.0"
iyy="0.1" iyz="0.0"
izz="0.005"/>
</inertial>
</link>
<joint name="joint1" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0 0 1" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="10.0" lower="0.0" upper="2.0" velocity="0.5"/>
<dynamics damping="1.0"/>
</joint>
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/one_DOF_robot</robotNamespace>
</plugin>
</gazebo>
</robot>
explaination
• Joint frame “joint 1”
• Rigidly linked with the parent: link1
<origin xyz ="0 0 0.5 " rpy ="0 0 0"/>
• Pose of Joint Frame
• Specified by describing: displacement & rotation of joint frame wrt parent
• Displaced 0.5m in 𝒛 & no change in orientation.
<joint name =" joint1 " type =" continuous ">
<axis xyz ="0 1 0"/>
• Link2 associated to link1 through revolute joint.
• If unspecified, joint axis of revolute joint: collinear with x-axis.
• Here, axis collinear with y-axis.
• In contrast with DH convention, which always uses the z–axis.
collision 碰撞属性
visual 形状大小
inertial 惯性属性
mass 重量 单位:Kg
使用gazebo 插件的时候需要对模型有所限制
<joint name="joint1" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0 0 1" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="10.0" lower="0.0" upper="2.0" velocity="0.5"/>
<dynamics damping="1.0"/>
</joint>
effort 力矩限制 单位n*m
velosity rad/s
damping 摩擦系数
gazebo
利用命令行加载模型
先运行
rosrun gazebo_ros gazebo
再运行
gazebo本身提供多种服务
以下程序就是利用各种服务,并将服务转化为话题发布出去,便于rqt_plot各种信息
先运行launch文件
<launch>
<param name="robot_description"
textfile="$(find minimal_robot_description)/minimal_robot_description.urdf"/>
<!-- Spawn a robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-param robot_description -urdf -model one_DOF_robot" />
</launch>
the minimal_robot_description.urdf
<?xml version="1.0"?>
<robot name="one_DOF_robot">
<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="world"/>
<joint name="glue_robot_to_world" type="fixed">
<parent link="world"/>
<child link="link1"/>
</joint>
<!-- Base Link -->
<link name="link1">
<collision>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.2 0.7"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.2 1"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<!-- Moveable Link -->
<link name="link2">
<collision>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="0.1"/>
<!--box size="0.15 0.15 0.8"-->
</geometry>
</collision>
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="0.1"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="0.1" ixy="0.0" ixz="0.0"
iyy="0.1" iyz="0.0"
izz="0.005"/>
</inertial>
</link>
<joint name="joint1" type="continuous">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0 0 1" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
</robot>
#include <ros/ros.h> //ALWAYS need to include this
#include <gazebo_msgs/GetModelState.h>
#include <gazebo_msgs/ApplyJointEffort.h>
#include <gazebo_msgs/GetJointProperties.h>
#include <sensor_msgs/JointState.h>
#include <string.h>
#include <stdio.h>
#include <std_msgs/Float64.h>
#include <math.h>
//some "magic number" global params:
const double Kp = 10.0; //controller gains
const double Kv = 3;
const double dt = 0.01;
//a simple saturation function; provide saturation threshold, sat_val, and arg to be saturated, val
double sat(double val, double sat_val) {
if (val > sat_val)
return (sat_val);
if (val< -sat_val)
return (-sat_val);
return val;
}
double min_periodicity(double theta_val) {
double periodic_val = theta_val;
while (periodic_val > M_PI) {
periodic_val -= 2 * M_PI;
}
while (periodic_val< -M_PI) {
periodic_val += 2 * M_PI;
}
return periodic_val;
}
double g_pos_cmd = 0.0; //position command input-- global var
void posCmdCB(const std_msgs::Float64& pos_cmd_msg) {
ROS_INFO("received value of pos_cmd is: %f", pos_cmd_msg.data);
g_pos_cmd = pos_cmd_msg.data;
}
bool test_services() {
bool service_ready = false;
if (!ros::service::exists("/gazebo/apply_joint_effort", true)) {
ROS_WARN("waiting for apply_joint_effort service");
return false;
}
if (!ros::service::exists("/gazebo/get_joint_properties", true)) {
ROS_WARN("waiting for /gazebo/get_joint_properties service");
return false;
}
ROS_INFO("services are ready");
return true;
}
int main(int argc, char **argv) {
//initializations:
ros::init(argc, argv, "minimal_joint_controller");
ros::NodeHandle nh;
ros::Duration half_sec(0.5);
// make sure services are available before attempting to proceed, else node will crash
while (!test_services()) {
ros::spinOnce();
half_sec.sleep();
}
ros::ServiceClient set_trq_client =
nh.serviceClient<gazebo_msgs::ApplyJointEffort>("/gazebo/apply_joint_effort");
ros::ServiceClient get_jnt_state_client =
nh.serviceClient<gazebo_msgs::GetJointProperties>("/gazebo/get_joint_properties");
gazebo_msgs::ApplyJointEffort effort_cmd_srv_msg;
gazebo_msgs::GetJointProperties get_joint_state_srv_msg;
ros::Publisher trq_publisher = nh.advertise<std_msgs::Float64>("jnt_trq", 1);
ros::Publisher vel_publisher = nh.advertise<std_msgs::Float64>("jnt_vel", 1);
ros::Publisher pos_publisher = nh.advertise<std_msgs::Float64>("jnt_pos", 1);
ros::Publisher joint_state_publisher = nh.advertise<sensor_msgs::JointState>("joint_states", 1);
ros::Subscriber pos_cmd_subscriber = nh.subscribe("pos_cmd", 1, posCmdCB);
std_msgs::Float64 trq_msg, q1_msg, q1dot_msg;
double q1, q1dot, q1_err, trq_cmd;
sensor_msgs::JointState joint_state_msg;
ros::Duration duration(dt);
ros::Rate rate_timer(1 / dt);
effort_cmd_srv_msg.request.joint_name = "joint1";
effort_cmd_srv_msg.request.effort = 0.0;
effort_cmd_srv_msg.request.duration = duration;
get_joint_state_srv_msg.request.joint_name = "joint1";
// set up the joint_state_msg fields to define a single joint,
// called joint1, and initial position and vel values of 0
joint_state_msg.header.stamp = ros::Time::now();
joint_state_msg.name.push_back("joint1");
joint_state_msg.position.push_back(0.0);
joint_state_msg.velocity.push_back(0.0);
//here is the main controller loop:
while (ros::ok()) {
get_jnt_state_client.call(get_joint_state_srv_msg);
q1 = get_joint_state_srv_msg.response.position[0];
q1_msg.data = q1;
pos_publisher.publish(q1_msg); //republish his val on topic jnt_pos
q1dot = get_joint_state_srv_msg.response.rate[0];
q1dot_msg.data = q1dot;
vel_publisher.publish(q1dot_msg);
joint_state_msg.header.stamp = ros::Time::now();
joint_state_msg.position[0] = q1;
joint_state_msg.velocity[0] = q1dot;
joint_state_publisher.publish(joint_state_msg);
q1_err = min_periodicity(g_pos_cmd - q1); //jnt angle err; watch for periodicity
trq_cmd = Kp * (q1_err) - Kv*q1dot;
trq_msg.data = trq_cmd;
trq_publisher.publish(trq_msg);
effort_cmd_srv_msg.request.effort = trq_cmd; // send torque command to Gazebo
set_trq_client.call(effort_cmd_srv_msg);
//make sure service call was successful
bool result = effort_cmd_srv_msg.response.success;
if (!result)
ROS_WARN("service call to apply_joint_effort failed!");
ros::spinOnce();
rate_timer.sleep();
}
}
运行后运行这个就发布消息了
rostopic pub pos_cmd std_msgs/Float64 1.0
绘图
rqt_plot /jnt_pos/data /jnt_trq/data /jnt_vel/data
利用内置的plugin
就要用到文章一开头的urdf了
There are 5 steps to set a ROS Joint controller as a Gazebo plugin:
- Joint field: include limits for joints and torques in URDF.
- Transmission field: include one for each joint to be controlled.
- Gazebo block: insert in URDF to import libgazebo_ros_control.so
- Controller Params: create a YAML file that declares controller gains
- Start Controller: load controller params & start controller w/ launch file
the launch
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find minimal_robot_description)/control_config/one_dof_ctl_params.yaml" command="load"/>
<param name="robot_description"
textfile="$(find minimal_robot_description)/minimal_robot_description_w_jnt_ctl.urdf"/>
<!-- Spawn a robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-param robot_description -urdf -model one_DOF_robot" />
<!--start up the controller plug-ins via the controller manager -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/one_DOF_robot" args="joint_state_controller joint1_position_controller"/>
</launch>
the yaml
one_DOF_robot:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
joint1_position_controller:
type: effort_controllers/JointPositionController
joint: joint1
pid: {p: 10.0, i: 10.0, d: 10.0, i_clamp_min: -10.0, i_clamp_max: 10.0}
one_DOF_robot joint1_position_controller joint1_position_controller
是自定义的 来自 urdf
发布命令
rostopic pub -r 10 /one_DOF_robot/joint1_position_controller/command std_msgs/Float64 1.0
plot
rqt_plot /one_DOF_robot/joint_states/position[0] /one_DOF_robot/joint_states/velocity[0] /one_DOF_robot/joint_states/effort[0]
删除gazebo后台程序
查看PID号(进程号)
ps aux | grep gazebo
kill -9 5825
you may need to install this before
sudo apt-get install ros-indigo-joint-state-controller // This will install joint_state_controller package
sudo apt-get install ros-indigo-effort-controllers //This will install Effort controller
sudo apt-get install ros-indigo-position-controllers // This will install position controllers
sudo apt-get install ros-indigo-gazebo-ros-control