Gentoo Archives: gentoo-commits

From: Alexis Ballier <aballier@g.o>
To: gentoo-commits@l.g.o
Subject: [gentoo-commits] repo/gentoo:master commit in: dev-ros/gazebo_ros_control/, dev-ros/gazebo_ros_control/files/
Date: Fri, 29 Jan 2016 00:05:06
Message-Id: 1454012743.8e1c93101a3d9f946c1278da7e69da3eaa7bf139.aballier@gentoo
1 commit: 8e1c93101a3d9f946c1278da7e69da3eaa7bf139
2 Author: Alexis Ballier <aballier <AT> gentoo <DOT> org>
3 AuthorDate: Thu Jan 28 20:23:08 2016 +0000
4 Commit: Alexis Ballier <aballier <AT> gentoo <DOT> org>
5 CommitDate: Thu Jan 28 20:25:43 2016 +0000
6 URL: https://gitweb.gentoo.org/repo/gentoo.git/commit/?id=8e1c9310
7
8 dev-ros/gazebo_ros_control: fix build with gazebo7
9
10 Package-Manager: portage-2.2.27
11 Signed-off-by: Alexis Ballier <aballier <AT> gentoo.org>
12
13 dev-ros/gazebo_ros_control/files/gazebo7.patch | 61 ++++++++++++++++++++++
14 .../gazebo_ros_control-2.5.1.ebuild | 1 +
15 2 files changed, 62 insertions(+)
16
17 diff --git a/dev-ros/gazebo_ros_control/files/gazebo7.patch b/dev-ros/gazebo_ros_control/files/gazebo7.patch
18 new file mode 100644
19 index 0000000..190756d
20 --- /dev/null
21 +++ b/dev-ros/gazebo_ros_control/files/gazebo7.patch
22 @@ -0,0 +1,61 @@
23 +commit b5303e692bb5dd2e4f4fc7932c7ec2c7e0b2e907
24 +Author: Steven Peters <scpeters@×××××××××××××.org>
25 +Date: Tue Apr 14 18:10:36 2015 -0700
26 +
27 + Use Joint::SetParam for joint velocity motors
28 +
29 + Before gazebo5, Joint::SetVelocity and SetMaxForce
30 + were used to set joint velocity motors.
31 + The API has changed in gazebo5, to use Joint::SetParam
32 + instead.
33 + The functionality is still available through the SetParam API.
34 +
35 + cherry-picked from indigo-devel
36 +
37 + Add ifdefs to fix build with gazebo2
38 +
39 + It was broken by #315.
40 + Fixes #321.
41 +
42 +diff --git a/gazebo_ros_control/src/default_robot_hw_sim.cpp b/gazebo_ros_control/src/default_robot_hw_sim.cpp
43 +index 249c8d3..1d9418d 100644
44 +--- a/gazebo_ros_control/src/default_robot_hw_sim.cpp
45 ++++ b/gazebo_ros_control/src/default_robot_hw_sim.cpp
46 +@@ -199,7 +199,7 @@ bool DefaultRobotHWSim::initSim(
47 + if (joint_control_methods_[j] != EFFORT)
48 + {
49 + // Initialize the PID controller. If no PID gain values are found, use joint->SetAngle() or
50 +- // joint->SetVelocity() to control the joint.
51 ++ // joint->SetParam("vel") to control the joint.
52 + const ros::NodeHandle nh(model_nh, "/gazebo_ros_control/pid_gains/" +
53 + joint_names_[j]);
54 + if (pid_controllers_[j].init(nh, true))
55 +@@ -216,10 +216,14 @@ bool DefaultRobotHWSim::initSim(
56 + }
57 + else
58 + {
59 +- // joint->SetMaxForce() must be called if joint->SetAngle() or joint->SetVelocity() are
60 +- // going to be called. joint->SetMaxForce() must *not* be called if joint->SetForce() is
61 ++ // joint->SetParam("fmax") must be called if joint->SetAngle() or joint->SetParam("vel") are
62 ++ // going to be called. joint->SetParam("fmax") must *not* be called if joint->SetForce() is
63 + // going to be called.
64 ++#if GAZEBO_MAJOR_VERSION > 2
65 ++ joint->SetParam("fmax", 0, joint_effort_limits_[j]);
66 ++#else
67 + joint->SetMaxForce(0, joint_effort_limits_[j]);
68 ++#endif
69 + }
70 + }
71 + }
72 +@@ -327,7 +331,11 @@ void DefaultRobotHWSim::writeSim(ros::Time time, ros::Duration period)
73 + break;
74 +
75 + case VELOCITY:
76 ++#if GAZEBO_MAJOR_VERSION > 2
77 ++ sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_velocity_command_[j]);
78 ++#else
79 + sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_command_[j]);
80 ++#endif
81 + break;
82 +
83 + case VELOCITY_PID:
84
85 diff --git a/dev-ros/gazebo_ros_control/gazebo_ros_control-2.5.1.ebuild b/dev-ros/gazebo_ros_control/gazebo_ros_control-2.5.1.ebuild
86 index a8ee997..65b2ca7 100644
87 --- a/dev-ros/gazebo_ros_control/gazebo_ros_control-2.5.1.ebuild
88 +++ b/dev-ros/gazebo_ros_control/gazebo_ros_control-2.5.1.ebuild
89 @@ -27,3 +27,4 @@ RDEPEND="
90 sci-electronics/gazebo
91 "
92 DEPEND="${RDEPEND}"
93 +PATCHES=( "${FILESDIR}/gazebo7.patch" )