Skip to content

Commit 86f2254

Browse files
authored
Merge pull request #226 from rickstaa/fix_gazebo_set_model_config_problem
feat(franka_gazebo): implement `set_franka_model_configuration` service
2 parents 5f90395 + bae0507 commit 86f2254

File tree

7 files changed

+40
-3
lines changed

7 files changed

+40
-3
lines changed

CHANGELOG.md

+1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ Requires `libfranka` >= 0.8.0
1313
* `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))
1414
* `franka_description`: `<xacro:franka_robot/>` macro now supports to customize the `parent` frame and its `xyz` + `rpy` offset
1515
* `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.
1617

1718
## 0.10.1 - 2022-09-15
1819

franka_gazebo/include/franka_gazebo/franka_hw_sim.h

+2
Original file line numberDiff line numberDiff line change
@@ -158,8 +158,10 @@ class FrankaHWSim : public gazebo_ros_control::RobotHWSim {
158158
ros::ServiceServer service_set_load_;
159159
ros::ServiceServer service_collision_behavior_;
160160
ros::ServiceServer service_user_stop_;
161+
ros::ServiceServer service_set_model_configuration_;
161162
ros::ServiceClient service_controller_list_;
162163
ros::ServiceClient service_controller_switch_;
164+
ros::ServiceClient service_gazebo_set_model_configuration_;
163165
std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>> action_recovery_;
164166

165167
std::vector<double> lower_force_thresholds_nominal_;

franka_gazebo/include/franka_gazebo/joint.h

+10
Original file line numberDiff line numberDiff line change
@@ -167,9 +167,19 @@ struct Joint {
167167
/// gains are ignored.
168168
control_toolbox::Pid velocity_controller;
169169

170+
/**
171+
* Sets the joint position.
172+
*/
173+
void setJointPosition(const double joint_position);
174+
170175
private:
171176
double lastVelocity = std::numeric_limits<double>::quiet_NaN();
172177
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_;
173183
};
174184

175185
} // namespace franka_gazebo

franka_gazebo/src/joint.cpp

+17
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,15 @@ void Joint::update(const ros::Duration& dt) {
99
return;
1010
}
1111

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+
1221
this->velocity = this->handle->GetVelocity(0);
1322
#if GAZEBO_MAJOR_VERSION >= 8
1423
double position = this->handle->Position(0);
@@ -111,4 +120,12 @@ bool Joint::isInCollision() const {
111120
bool Joint::isInContact() const {
112121
return std::abs(this->effort - this->command) > this->contact_threshold;
113122
}
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+
114131
} // namespace franka_gazebo

franka_msgs/CMakeLists.txt

+4-3
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
cmake_minimum_required(VERSION 3.4)
22
project(franka_msgs)
33

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)
55

66
add_message_files(FILES Errors.msg FrankaState.msg)
77

@@ -10,13 +10,14 @@ add_service_files(FILES
1010
SetEEFrame.srv
1111
SetForceTorqueCollisionBehavior.srv
1212
SetFullCollisionBehavior.srv
13+
SetJointConfiguration.srv
1314
SetJointImpedance.srv
1415
SetKFrame.srv
1516
SetLoad.srv
1617
)
1718

1819
add_action_files(FILES ErrorRecovery.action)
1920

20-
generate_messages(DEPENDENCIES std_msgs actionlib_msgs)
21+
generate_messages(DEPENDENCIES std_msgs sensor_msgs actionlib_msgs)
2122

22-
catkin_package(CATKIN_DEPENDS message_runtime std_msgs actionlib_msgs)
23+
catkin_package(CATKIN_DEPENDS message_runtime std_msgs sensor_msgs actionlib_msgs)

franka_msgs/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
<build_depend>message_generation</build_depend>
1717

1818
<depend>std_msgs</depend>
19+
<depend>sensor_msgs</depend>
1920
<depend>actionlib_msgs</depend>
2021

2122
<exec_depend>message_runtime</exec_depend>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
string[] joint_names
2+
float64[] joint_positions
3+
---
4+
bool success
5+
string error

0 commit comments

Comments
 (0)