OrebroUniversity版本的ROS版本升级(Gazebo通过,实机未通过)
从Kinetic升级至Melodic
KTH的fork
- https://github.com/kth-ros-pkg/yumi
sudo apt install ros-melodic-industrial-core- melodic分支,yumi_hw/src/yumi_hw_ifce_node.cpp第166行
改为control_period_pub.publish(period.toSec());std_msgs::Float64 period_msg; period_msg.data = period.toSec(); control_period_pub.publish(period_msg); - 安装
sudo apt install ros-melodic-hector-xacro-tools(Noetic可能不需要?) - 修改URDF文件 Github issue
Just like ritalaezza, my solution was to add the following line in
yumi.urdf.xacro, just after the<!--yumi-->comment:<xacro:property name="yumi_parent" value="world" /> - 回到workspace目录下
source ./devel/setup.bash
OrebroUniversity原始版本
-
安装参考
sudo apt-get install \ python-pip \ protobuf-compiler \ protobuf-c-compiler \ ros-$ROS_DISTRO-control-toolbox \ ros-$ROS_DISTRO-controller-interface \ ros-$ROS_DISTRO-controller-manager \ ros-$ROS_DISTRO-effort-controllers \ ros-$ROS_DISTRO-force-torque-sensor-controller \ ros-$ROS_DISTRO-gazebo-ros-control \ ros-$ROS_DISTRO-joint-limits-interface \ ros-$ROS_DISTRO-joint-state-publisher \ ros-$ROS_DISTRO-joint-state-controller \ ros-$ROS_DISTRO-joint-trajectory-controller \ ros-$ROS_DISTRO-moveit-commander \ ros-$ROS_DISTRO-moveit-core \ ros-$ROS_DISTRO-moveit-planners \ ros-$ROS_DISTRO-moveit-ros-move-group \ ros-$ROS_DISTRO-moveit-ros-planning \ ros-$ROS_DISTRO-moveit-ros-visualization \ ros-$ROS_DISTRO-moveit-simple-controller-manager \ ros-$ROS_DISTRO-position-controllers \ ros-$ROS_DISTRO-rqt-joint-trajectory-controller \ ros-$ROS_DISTRO-transmission-interface \ ros-$ROS_DISTRO-velocity-controllerspip install --user pyftpdlib pip install --user --upgrade pyassimpsudo apt install ros-melodic-industrial-core -
升级代码参考GitHub
gazebo_mimic/src/gazebo_mimic_plugin/mimic_plugin.cpp中event::Events::DisconnectWorldUpdateBegin(this->updateConnection);tothis->updateConnection.reset();GetAngle(0).Radian();toPosition(0)
yumi_hw/src/yumi_hw.cpp中const boost::shared_ptr<const urdf::Joint>toconst std::shared_ptr<const urdf::Joint>- 修改URDF文件
yumi_description/urdf/yumi.urdf.xacroGithub issueJust like ritalaezza, my solution was to add the following line in
yumi.urdf.xacro, just after the<!--yumi-->comment:<xacro:property name="yumi_parent" value="world" />
-
回到workspace目录下
source ./devel/setup.bash -
安装
sudo apt install ros-melodic-hector-xacro-tools -
在workspace目录下
source ./devel/setup.bash -
启动Gazebo
rosrun gazebo_ros gazebo- 启动Gazebo时的问题
[Err] [REST.cc:205] Error in REST request libcurl: (51) SSL: no alternative certificate subject name matches target host name 'api.ignitionfuel.org'参考 对~/.ignition/fuel/config.yaml进行修改- url: https://api.ignitionfuel.org + url: https://api.ignitionrobotics.org- 使用虚拟机参考:
$ echo "export SVGA_VGPU10=0" >> ~/.profileSideote: If you’d add it to ~/.bashrc starting gazebo from gui or other terminals than bash would still be broken.
- 启动Gazebo时的问题
在修改代码(KTH的melodic分支)的基础上移植到Noetic
-
准备工作
sudo apt-get install \ python3-pip \ protobuf-compiler \ protobuf-c-compiler \ ros-$ROS_DISTRO-control-toolbox \ ros-$ROS_DISTRO-controller-interface \ ros-$ROS_DISTRO-controller-manager \ ros-$ROS_DISTRO-effort-controllers \ ros-$ROS_DISTRO-force-torque-sensor-controller \ ros-$ROS_DISTRO-gazebo-ros-control \ ros-$ROS_DISTRO-joint-limits-interface \ ros-$ROS_DISTRO-joint-state-publisher \ ros-$ROS_DISTRO-joint-state-controller \ ros-$ROS_DISTRO-joint-trajectory-controller \ ros-$ROS_DISTRO-moveit-commander \ ros-$ROS_DISTRO-moveit-core \ ros-$ROS_DISTRO-moveit-planners \ ros-$ROS_DISTRO-moveit-ros-move-group \ ros-$ROS_DISTRO-moveit-ros-planning \ ros-$ROS_DISTRO-moveit-ros-visualization \ ros-$ROS_DISTRO-moveit-simple-controller-manager \ ros-$ROS_DISTRO-position-controllers \ ros-$ROS_DISTRO-rqt-joint-trajectory-controller \ ros-$ROS_DISTRO-transmission-interface \ ros-$ROS_DISTRO-velocity-controllerspip3 install --user pyftpdlib pip3 install --user --upgrade pyassimpsudo apt install ros-$ROS_DISTRO-hector-xacro-tools- 编译abb_driver
# change to the root of the Catkin workspace cd $HOME/catkin_ws # retrieve the latest development version of the abb_driver repository. If you'd rather # use the latest released version, replace 'kinetic-devel' with 'kinetic' git clone -b melodic-devel https://github.com/ros-industrial/abb_driver.git src/abb_driver # check for and install missing build dependencies. # first: update the local database rosdep update # now install dependencies, again using rosdep. # Note: this may install additional packages, depending on the software already present # on the machine. # Be sure to change 'kinetic' to whichever ROS version you are using rosdep install --from-paths src/ --ignore-src --rosdistro noetic # build the workspace (using catkin_tools) catkin build - 编译industrial_core
# change to the root of the Catkin workspace $ cd $HOME/catkin_ws # retrieve the latest development version of industrial_core. If you'd rather # use the latest released version, replace 'melodic-devel' with 'melodic' $ git clone -b melodic-devel https://github.com/ros-industrial/industrial_core.git src/industrial_core # check build dependencies. Note: this may install additional packages, # depending on the software installed on the machine $ rosdep update # be sure to change 'melodic' to whichever ROS release you are using $ rosdep install --from-paths src/ --ignore-src --rosdistro noetic # build the workspace (using catkin_tools) $ catkin build - 修改启动代码(参考),如
yumi_gazebo_pos_control.launch中<param name="robot_description" command="$(find xacro)/xacro.py改为<param name="robot_description" command="$(find xacro)/xacro否则会报错RLException: Invalid <param> tag: Cannot load command parameter [robot_description]: no such command [['/opt/ros/noetic/share/xacro/xacro.py' - Gazebo启动参数
- 同时启动Gazebo图形界面:
在
<!-- Call Gazebo-->中将gui的标签改为true - 过时参数:
- headless
- 同时启动Gazebo图形界面:
在
- 编译abb_driver
Gazebo
- world文件位置
\usr\share\gazebo-11\worlds
Moveit
-
roslaunch yumi_moveit_config demo.launch
-
配置 TRAC-IT
-
安装
sudo apt-get install ros-\$ROS_DISTRO-trac-ik -
配置
Find the MoveIt
kinematics.yamlfile created for your robot. Replacekinematics_solver:kdl_kinematics_plugin/KDLKinematicsPlugin(or similar) withkinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin- 编译
catkin build, 否则会出现错误[ERROR] [1638920131.829167677]: The kinematics plugin (left_arm) failed to load. Error: Failed to load library /opt/ros/noetic/lib//libtrac_ik_kinematics_plugin.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = libmoveit_kinematics_base.so.1.1.6: cannot open shared object file: No such file or directory) [ERROR] [1638920131.829202049]: Kinematics solver could not be instantiated for joint group left_arm.
- 编译
-
-
在
yumi_moveit_config/launch/moveit.rviz中修改Loop Animation为false (否则plan后会一直显示plan的动画) -
可以将
Query Goal State修改为false