-
Notifications
You must be signed in to change notification settings - Fork 128
Giving force mode parameters as arguments when calling startForceMode #208
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 2 commits
e1797f3
535b083
768be7a
683e542
83662d6
9ca40b0
6a37208
9728732
a7926d4
179dd05
fb1da3e
060a493
8ff93ae
d384b21
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -109,10 +109,19 @@ class ScriptCommandInterface : public ReverseInterface | |
| * axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual | ||
| * tcp position and the one set by the program | ||
| * | ||
| * \param damping_factor (Double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025 | ||
|
||
| * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0 | ||
| * is no damping, here the robot will maintain the speed. | ||
| * | ||
| * \param gain_scaling_factor (Double) Scales the gain in force mode. scaling parameter is in range [0,2], default | ||
|
||
| * is 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard | ||
| * surfaces. | ||
| * | ||
| * \returns True, if the write was performed successfully, false otherwise. | ||
| */ | ||
| bool startForceMode(const vector6d_t* task_frame, const vector6uint32_t* selection_vector, const vector6d_t* wrench, | ||
| const unsigned int type, const vector6d_t* limits); | ||
| const unsigned int type, const vector6d_t* limits, double damping_factor, | ||
| double gain_scaling_factor); | ||
|
|
||
| /*! | ||
| * \brief Stop force mode and put the robot into normal operation mode. | ||
|
|
@@ -178,7 +187,7 @@ class ScriptCommandInterface : public ReverseInterface | |
| }; | ||
|
|
||
| bool client_connected_; | ||
| static const int MAX_MESSAGE_LENGTH = 26; | ||
| static const int MAX_MESSAGE_LENGTH = 28; | ||
|
|
||
| std::function<void(ToolContactResult)> handle_tool_contact_result_; | ||
| }; | ||
|
|
||
Uh oh!
There was an error while loading. Please reload this page.