File tree 7 files changed +40
-3
lines changed
7 files changed +40
-3
lines changed Original file line number Diff line number Diff line change @@ -13,6 +13,7 @@ Requires `libfranka` >= 0.8.0
13
13
* ` franka_gazebo ` : ` FrankaHWSim ` only acts on joints belonging to a Franka robot. This allows to combine a Franka robot and others (like mobile platforms) in same URDF ([ #313 ] ( https://github.com/frankaemika/franka_ros/issues/313 ) )
14
14
* ` franka_description ` : ` <xacro:franka_robot/> ` macro now supports to customize the ` parent ` frame and its ` xyz ` + ` rpy ` offset
15
15
* ` franka_hw ` : Fix the bug where the previous controller is still running after switching the controller. ([ #326 ] ( https://github.com/frankaemika/franka_ros/issues/326 ) )
16
+ * ` franka_gazebo ` : Add ` set_franka_model_configuration ` service.
16
17
17
18
## 0.10.1 - 2022-09-15
18
19
Original file line number Diff line number Diff line change @@ -158,8 +158,10 @@ class FrankaHWSim : public gazebo_ros_control::RobotHWSim {
158
158
ros::ServiceServer service_set_load_;
159
159
ros::ServiceServer service_collision_behavior_;
160
160
ros::ServiceServer service_user_stop_;
161
+ ros::ServiceServer service_set_model_configuration_;
161
162
ros::ServiceClient service_controller_list_;
162
163
ros::ServiceClient service_controller_switch_;
164
+ ros::ServiceClient service_gazebo_set_model_configuration_;
163
165
std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>> action_recovery_;
164
166
165
167
std::vector<double > lower_force_thresholds_nominal_;
Original file line number Diff line number Diff line change @@ -167,9 +167,19 @@ struct Joint {
167
167
// / gains are ignored.
168
168
control_toolbox::Pid velocity_controller;
169
169
170
+ /* *
171
+ * Sets the joint position.
172
+ */
173
+ void setJointPosition (const double joint_position);
174
+
170
175
private:
171
176
double lastVelocity = std::numeric_limits<double >::quiet_NaN();
172
177
double lastAcceleration = std::numeric_limits<double >::quiet_NaN();
178
+
179
+ // Track joint position set requests
180
+ bool setPositionRequested_ = false ;
181
+ double requestedPosition_ = 0.0 ;
182
+ std::mutex requestedPositionMutex_;
173
183
};
174
184
175
185
} // namespace franka_gazebo
Original file line number Diff line number Diff line change @@ -9,6 +9,15 @@ void Joint::update(const ros::Duration& dt) {
9
9
return ;
10
10
}
11
11
12
+ // Apply 'setJointPosition' position request.
13
+ if (this ->setPositionRequested_ ) {
14
+ std::lock_guard<std::mutex> lock (this ->requestedPositionMutex_ );
15
+ this ->position = this ->requestedPosition_ ;
16
+ this ->desired_position = this ->requestedPosition_ ;
17
+ this ->stop_position = this ->requestedPosition_ ;
18
+ this ->setPositionRequested_ = false ;
19
+ }
20
+
12
21
this ->velocity = this ->handle ->GetVelocity (0 );
13
22
#if GAZEBO_MAJOR_VERSION >= 8
14
23
double position = this ->handle ->Position (0 );
@@ -111,4 +120,12 @@ bool Joint::isInCollision() const {
111
120
bool Joint::isInContact () const {
112
121
return std::abs (this ->effort - this ->command ) > this ->contact_threshold ;
113
122
}
123
+
124
+ void Joint::setJointPosition (const double joint_position) {
125
+ // NOTE: Joint position is set in update() method to prevent racing conditions.
126
+ std::lock_guard<std::mutex> lock (this ->requestedPositionMutex_ );
127
+ this ->requestedPosition_ = joint_position;
128
+ this ->setPositionRequested_ = true ;
129
+ }
130
+
114
131
} // namespace franka_gazebo
Original file line number Diff line number Diff line change 1
1
cmake_minimum_required (VERSION 3.4)
2
2
project (franka_msgs)
3
3
4
- find_package (catkin REQUIRED COMPONENTS message_generation std_msgs actionlib_msgs)
4
+ find_package (catkin REQUIRED COMPONENTS message_generation std_msgs sensor_msgs actionlib_msgs)
5
5
6
6
add_message_files(FILES Errors.msg FrankaState.msg)
7
7
@@ -10,13 +10,14 @@ add_service_files(FILES
10
10
SetEEFrame.srv
11
11
SetForceTorqueCollisionBehavior.srv
12
12
SetFullCollisionBehavior.srv
13
+ SetJointConfiguration.srv
13
14
SetJointImpedance.srv
14
15
SetKFrame.srv
15
16
SetLoad.srv
16
17
)
17
18
18
19
add_action_files(FILES ErrorRecovery.action)
19
20
20
- generate_messages(DEPENDENCIES std_msgs actionlib_msgs)
21
+ generate_messages(DEPENDENCIES std_msgs sensor_msgs actionlib_msgs)
21
22
22
- catkin_package(CATKIN_DEPENDS message_runtime std_msgs actionlib_msgs)
23
+ catkin_package(CATKIN_DEPENDS message_runtime std_msgs sensor_msgs actionlib_msgs)
Original file line number Diff line number Diff line change 16
16
<build_depend >message_generation</build_depend >
17
17
18
18
<depend >std_msgs</depend >
19
+ <depend >sensor_msgs</depend >
19
20
<depend >actionlib_msgs</depend >
20
21
21
22
<exec_depend >message_runtime</exec_depend >
Original file line number Diff line number Diff line change
1
+ string[] joint_names
2
+ float64[] joint_positions
3
+ ---
4
+ bool success
5
+ string error
You can’t perform that action at this time.
0 commit comments