├── LICENSE
├── README.md
├── arm_controllers
├── CMakeLists.txt
├── cfg
│ └── PassivityControllerParams.cfg
├── controller_plugins.xml
├── include
│ └── utils
│ │ ├── pseudo_inversion.h
│ │ └── skew_symmetric.h
├── msg
│ └── ControllerJointState.msg
├── package.xml
└── src
│ ├── adaptive_impedance_controller.cpp
│ ├── computed_torque_clik_controller.cpp
│ ├── computed_torque_controller.cpp
│ ├── gravity_comp_controller.cpp
│ ├── passivity_controller.cpp
│ └── time_delay_controller.cpp
└── elfin
├── elfin_description
├── CMakeLists.txt
├── meshes
│ ├── elfin10
│ │ ├── elfin_base.STL
│ │ ├── elfin_link1.STL
│ │ ├── elfin_link2.STL
│ │ ├── elfin_link3.STL
│ │ ├── elfin_link4.STL
│ │ ├── elfin_link5.STL
│ │ └── elfin_link6.STL
│ ├── elfin3
│ │ ├── elfin_base.STL
│ │ ├── elfin_link1.STL
│ │ ├── elfin_link2.STL
│ │ ├── elfin_link3.STL
│ │ ├── elfin_link4.STL
│ │ ├── elfin_link5.STL
│ │ └── elfin_link6.STL
│ └── elfin5
│ │ ├── elfin_base.STL
│ │ ├── elfin_link1.STL
│ │ ├── elfin_link2.STL
│ │ ├── elfin_link3.STL
│ │ ├── elfin_link4.STL
│ │ ├── elfin_link5.STL
│ │ └── elfin_link6.STL
├── package.xml
└── urdf
│ ├── box.urdf.xacro
│ ├── box_circle.urdf.xacro
│ ├── elfin3.urdf.xacro
│ ├── elfin3_experiment1.urdf.xacro
│ ├── elfin3_no_fric_no_joint_limit.urdf.xacro
│ ├── elfin_robot.gazebo
│ ├── elfin_robot_experiment1.gazebo
│ ├── elfin_transmission.xacro
│ ├── elfin_transmission_experiment1.xacro
│ └── materials.xacro
└── elfin_gazebo
├── .vscode
├── c_cpp_properties.json
└── settings.json
├── CMakeLists.txt
├── config
├── adaptive_impedance_controller.yaml
├── computed_torque_clik_controller.yaml
├── computed_torque_controller.yaml
├── gravity_comp_controller.yaml
├── passivity_controller.yaml
└── time_delay_controller.yaml
├── launch
├── elfin3_empty_world.launch
├── elfin3_experiment1_world.launch
├── elfin3_experiment2_world.launch
├── elfin3_no_fric_no_joint_limit_world.launch
├── gravity_comp_controller_perspective
│ ├── joint1_effort.perspective
│ ├── joint1_error.perspective
│ ├── joint1_state.perspective
│ ├── joint2_effort.perspective
│ ├── joint2_error.perspective
│ ├── joint2_state.perspective
│ ├── joint3_effort.perspective
│ ├── joint3_error.perspective
│ ├── joint3_state.perspective
│ ├── joint4_effort.perspective
│ ├── joint4_error.perspective
│ ├── joint4_state.perspective
│ ├── joint5_effort.perspective
│ ├── joint5_error.perspective
│ ├── joint5_state.perspective
│ ├── joint6_effort.perspective
│ ├── joint6_error.perspective
│ ├── joint6_state.perspective
│ └── tuning.perspective
├── passivity_controller_perspective
│ ├── joint1_effort.perspective
│ ├── joint1_error.perspective
│ ├── joint1_state.perspective
│ ├── joint2_effort.perspective
│ ├── joint2_error.perspective
│ ├── joint2_state.perspective
│ ├── joint3_effort.perspective
│ ├── joint3_error.perspective
│ ├── joint3_state.perspective
│ ├── joint4_effort.perspective
│ ├── joint4_error.perspective
│ ├── joint4_state.perspective
│ ├── joint5_effort.perspective
│ ├── joint5_error.perspective
│ ├── joint5_state.perspective
│ ├── joint6_effort.perspective
│ ├── joint6_error.perspective
│ ├── joint6_state.perspective
│ └── tuning.perspective
├── rqt_plot.launch
└── time_delay_controller_perspective
│ ├── joint1_error.perspective
│ ├── joint1_state.perspective
│ ├── joint2_error.perspective
│ ├── joint2_state.perspective
│ ├── joint3_error.perspective
│ ├── joint3_state.perspective
│ ├── joint4_error.perspective
│ ├── joint4_state.perspective
│ ├── joint5_error.perspective
│ ├── joint5_state.perspective
│ ├── joint6_error.perspective
│ └── joint6_state.perspective
└── package.xml
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2017
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | Robot arm control tutorial with ros-control, moveit, etc.
2 |
3 | arm_controllers is general robot arm controller.
4 | Elfin is 6-dof manipulator. elfin_description, elfin_gazebo is forked from [3], elfin_launch are added. elfin_control has controller and gain in yaml file.
5 |
6 | ## Introduction
7 | Implemented various control algorithm on 6-dof Elfin manipulator simulation using ros-control frameworks.
8 |
9 | ## How to run
10 | ### Prerequisite
11 | Install gazebo-ros-pkgs and gazebo-ros-control
12 |
13 | $ sudo apt-get install ros-noetic-gazebo-ros-pkgs ros-noetic-gazebo-ros-control
14 |
15 | Install ros-controllers
16 |
17 | $ sudo apt-get install ros-noetic-ros-controllers
18 |
19 | ### Download and build
20 |
21 | $ cd ~/catkin_ws/src
22 | $ git clone https://github.com/modulabs/arm-control.git
23 | $ cd ~/catkin_ws/
24 | $ catkin_make
25 |
26 | ### Run
27 | Depending on the controller you want to run, use suitable launch file.
28 | If you want to use motion controller in joint space, then you may choose this controllers as follows:
29 |
30 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=gravity_comp_controller
31 | or
32 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=time_delay_controller
33 | or
34 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=computed_torque_controller
35 | or
36 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=computed_torque_clik_controller
37 | or
38 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=passivity_controller
39 |
40 | If you want to use motion controller in task space, then you may choose this controllers as follows:
41 |
42 | $ roslaunch elfin_gazebo elfin3_empty_world.launch controller:=computed_torque_clik_controller
43 |
44 | If you want to use motion and force controller in task space, then you may choose this controllers as follows:
45 |
46 | $ roslaunch elfin_gazebo elfin3_experiment1_world.launch controller:=adaptive_impedance_controller
47 | or
48 | $ roslaunch elfin_gazebo elfin3_experiment2_world.launch controller:=adaptive_impedance_controller
49 |
50 | If you want to plot data in rqt graph, use rqt_plot.launch file. Customize perspective files to plot data you need.
51 |
52 | $ roslaunch rqt_plot.launch controller:=gravity_comp_controller
53 |
54 | ## Reference
55 | 1. [ros-control](http://wiki.ros.org/ros_control)
56 | 2. [Write a new ros-controller](https://github.com/ros-controls/ros_control/wiki/controller_interface)
57 | 3. [Elfin manipulator](http://wiki.ros.org/Robots/Elfin)
58 | 4. [Tomei, A Simple PD Controller for Robots with Elastic Joints](https://ieeexplore.ieee.org/document/90238)
59 | 5. [Slotine, On the Adaptive Control of Robot Manipulators](https://journals.sagepub.com/doi/10.1177/027836498700600303)
60 | 6. [Duan Jinjun, Adaptive variable impedance control](https://dl.acm.org/doi/10.1016/j.robot.2018.01.009)
61 |
--------------------------------------------------------------------------------
/arm_controllers/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(arm_controllers)
3 |
4 | find_package(catkin REQUIRED COMPONENTS
5 | angles
6 | controller_interface
7 | control_msgs
8 | urdf
9 | kdl_parser
10 | realtime_tools
11 | dynamic_reconfigure
12 | )
13 |
14 | # Dynamics reconfigure
15 | generate_dynamic_reconfigure_options(
16 | cfg/PassivityControllerParams.cfg
17 | )
18 |
19 | # message
20 | add_message_files(FILES ControllerJointState.msg)
21 | generate_messages(DEPENDENCIES std_msgs)
22 |
23 | # include
24 | include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})
25 |
26 | catkin_package(
27 | CATKIN_DEPENDS
28 | angles
29 | controller_interface
30 | control_msgs
31 | urdf
32 | kdl_parser
33 | realtime_tools
34 | dynamic_reconfigure
35 | LIBRARIES ${PROJECT_NAME}
36 | )
37 |
38 | add_library(${PROJECT_NAME}
39 | src/time_delay_controller.cpp
40 | src/gravity_comp_controller.cpp
41 | src/computed_torque_controller.cpp
42 | src/computed_torque_clik_controller.cpp
43 | src/adaptive_impedance_controller.cpp
44 | src/passivity_controller.cpp
45 | )
46 |
47 | target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
48 |
49 | add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg)
50 |
51 | install(DIRECTORY include/${PROJECT_NAME}/
52 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
53 |
54 | install(TARGETS ${PROJECT_NAME}
55 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
56 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
57 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
58 | )
59 |
60 |
--------------------------------------------------------------------------------
/arm_controllers/cfg/PassivityControllerParams.cfg:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | PACKAGE='arm_controllers'
3 |
4 | from dynamic_reconfigure.parameter_generator_catkin import *
5 | gen = ParameterGenerator()
6 |
7 | # Name Type Level Description Default Min Max
8 | gen.add( "alpha" , double_t, 1, "Alpha gain.", 0.1, -1000, 1000)
9 | # gen.add( "p" , double_t, 1, "Proportional gain.", 10.0, -100000, 100000)
10 | # gen.add( "i" , double_t, 1, "Integral gain.", 1.0, -1000, 1000)
11 | # gen.add( "d" , double_t, 1, "Derivative gain.", 1.0, -1000, 1000)
12 |
13 | # PkgName #NodeName #Prefix for generated .h include file, e.g. ParametersConfig.py
14 | exit(gen.generate(PACKAGE, "passivity_controller", "PassivityControllerParams"))
--------------------------------------------------------------------------------
/arm_controllers/controller_plugins.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | Time Delay Controller
6 |
7 |
8 |
9 |
10 |
11 | Gravity Compensation Controller
12 |
13 |
14 |
15 |
16 |
17 | Computed Torque Controller
18 |
19 |
20 |
21 |
22 |
23 | Computed Torque Controller with Closed Loop Inverse Kinematics
24 |
25 |
26 |
27 |
28 |
29 | Adaptive Impedance Controller
30 |
31 |
32 |
33 |
34 |
35 | Passivity Based Controller
36 |
37 |
38 |
39 |
40 |
--------------------------------------------------------------------------------
/arm_controllers/include/utils/pseudo_inversion.h:
--------------------------------------------------------------------------------
1 | // Author: Enrico Corvaglia
2 | // pseudo_inverse() computes the pseudo inverse of matrix M_ using SVD decomposition (can choose between damped and not)
3 | // returns the pseudo inverted matrix M_pinv_
4 |
5 | #ifndef PSEUDO_INVERSION_H
6 | #define PSEUDO_INVERSION_H
7 |
8 | #include
9 | #include
10 | #include
11 | using namespace Eigen;
12 |
13 | inline void pseudo_inverse(const Eigen::MatrixXd &M_, Eigen::MatrixXd &M_pinv_,bool damped = true)
14 | {
15 | double lambda_ = damped?0.2:0.0;
16 |
17 | JacobiSVD svd(M_, ComputeFullU | ComputeFullV);
18 | JacobiSVD::SingularValuesType sing_vals_ = svd.singularValues();
19 | MatrixXd S_ = M_; // copying the dimensions of M_, its content is not needed.
20 | S_.setZero();
21 |
22 | for (int i = 0; i < sing_vals_.size(); i++)
23 | S_(i,i) = (sing_vals_(i))/(sing_vals_(i)*sing_vals_(i) + lambda_*lambda_);
24 |
25 | M_pinv_ = MatrixXd(svd.matrixV()*S_.transpose()*svd.matrixU().transpose());
26 | }
27 |
28 | #endif
29 |
--------------------------------------------------------------------------------
/arm_controllers/include/utils/skew_symmetric.h:
--------------------------------------------------------------------------------
1 | // Author: Enrico Corvaglia
2 | // skew_symmetric() takes a vector as input and apply it the skew-symmetric operator
3 | // returns the related skew-symmetric matrix
4 |
5 | #ifndef SKEW_SYMMETRIC_H
6 | #define SKEW_SYMMETRIC_H
7 |
8 | #include
9 | #include
10 |
11 |
12 | inline void skew_symmetric(KDL::Vector &v_, Eigen::Matrix &skew_mat_)
13 | {
14 | skew_mat_ = Eigen::Matrix::Zero();
15 |
16 | skew_mat_(0,1) = -v_(2);
17 | skew_mat_(0,2) = v_(1);
18 | skew_mat_(1,0) = v_(2);
19 | skew_mat_(1,2) = -v_(0);
20 | skew_mat_(2,0) = -v_(1);
21 | skew_mat_(2,1) = v_(0);
22 | }
23 |
24 | #endif
--------------------------------------------------------------------------------
/arm_controllers/msg/ControllerJointState.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | string[] name
3 | float64[] command
4 | float64[] command_dot
5 | float64[] state
6 | float64[] state_dot
7 | float64[] error
8 | float64[] error_dot
9 | float64[] effort_command
10 | float64[] effort_feedforward
11 | float64[] effort_feedback
--------------------------------------------------------------------------------
/arm_controllers/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | arm_controllers
4 | 0.0.3
5 | Robot Arm Controllers
6 |
7 | kyungmin
8 | Hancheol Choi
9 | Jungyeong kyungmin5257
10 |
11 |
12 | MIT
13 |
14 | catkin
15 | controller_interface
16 | urdf
17 | control_msgs
18 | kdl_parser
19 | realtime_tools
20 | angles
21 | dynamic_reconfigure
22 |
23 | controller_interface
24 | urdf
25 | control_msgs
26 | kdl_parser
27 | realtime_tools
28 | angles
29 | dynamic_reconfigure
30 |
31 |
32 |
33 |
34 |
35 |
36 |
--------------------------------------------------------------------------------
/arm_controllers/src/gravity_comp_controller.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 |
6 | #include
7 | #include
8 | #include
9 |
10 | #include
11 |
12 | #include
13 | #include
14 | #include
15 | #include
16 | #include
17 |
18 | #include
19 |
20 | #include "arm_controllers/ControllerJointState.h"
21 |
22 | #define PI 3.141592
23 | #define D2R PI/180.0
24 | #define R2D 180.0/PI
25 |
26 | namespace arm_controllers{
27 |
28 | class GravityCompController: public controller_interface::Controller
29 | {
30 | public:
31 | ~GravityCompController()
32 | {
33 | command_sub_.shutdown();
34 | }
35 |
36 | bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n)
37 | {
38 | loop_count_ = 0;
39 | // List of controlled joints
40 | if (!n.getParam("joints", joint_names_))
41 | {
42 | ROS_ERROR("Could not find joint name");
43 | return false;
44 | }
45 | n_joints_ = joint_names_.size();
46 |
47 | if(n_joints_ == 0)
48 | {
49 | ROS_ERROR("List of joint names is empty.");
50 | return false;
51 | }
52 |
53 | // urdf
54 | urdf::Model urdf;
55 | if (!urdf.initParam("robot_description"))
56 | {
57 | ROS_ERROR("Failed to parse urdf file");
58 | return false;
59 | }
60 |
61 | // joint handle
62 | for(int i=0; igetHandle(joint_names_[i]));
67 | }
68 | catch (const hardware_interface::HardwareInterfaceException& e)
69 | {
70 | ROS_ERROR_STREAM("Exception thrown: " << e.what());
71 | return false;
72 | }
73 |
74 | urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(joint_names_[i]);
75 | if (!joint_urdf)
76 | {
77 | ROS_ERROR("Could not find joint '%s' in urdf", joint_names_[i].c_str());
78 | return false;
79 | }
80 | joint_urdfs_.push_back(joint_urdf);
81 | }
82 |
83 | // kdl parser
84 | if (!kdl_parser::treeFromUrdfModel(urdf, kdl_tree_)){
85 | ROS_ERROR("Failed to construct kdl tree");
86 | return false;
87 | }
88 |
89 | // kdl chain
90 | std::string root_name, tip_name;
91 | if (!n.getParam("root_link", root_name))
92 | {
93 | ROS_ERROR("Could not find root link name");
94 | return false;
95 | }
96 | if (!n.getParam("tip_link", tip_name))
97 | {
98 | ROS_ERROR("Could not find tip link name");
99 | return false;
100 | }
101 | if(!kdl_tree_.getChain(root_name, tip_name, kdl_chain_))
102 | {
103 | ROS_ERROR_STREAM("Failed to get KDL chain from tree: ");
104 | ROS_ERROR_STREAM(" "< "<(n_joints_, 0.0));
152 | command_sub_ = n.subscribe("command", 1, &GravityCompController::commandCB, this);
153 |
154 | // Start realtime state publisher
155 | controller_state_pub_.reset(
156 | new realtime_tools::RealtimePublisher(n, "state", 1));
157 |
158 | controller_state_pub_->msg_.header.stamp = ros::Time::now();
159 | for (size_t i=0; imsg_.name.push_back(joint_names_[i]);
162 | controller_state_pub_->msg_.command.push_back(0.0);
163 | controller_state_pub_->msg_.command_dot.push_back(0.0);
164 | controller_state_pub_->msg_.state.push_back(0.0);
165 | controller_state_pub_->msg_.state_dot.push_back(0.0);
166 | controller_state_pub_->msg_.error.push_back(0.0);
167 | controller_state_pub_->msg_.error_dot.push_back(0.0);
168 | controller_state_pub_->msg_.effort_command.push_back(0.0);
169 | controller_state_pub_->msg_.effort_feedforward.push_back(0.0);
170 | controller_state_pub_->msg_.effort_feedback.push_back(0.0);
171 | }
172 |
173 | return true;
174 | }
175 |
176 | void starting(const ros::Time& time)
177 | {
178 | // get joint positions
179 | for(size_t i=0; idata.size()!=n_joints_)
191 | {
192 | ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!");
193 | return;
194 | }
195 | commands_buffer_.writeFromNonRT(msg->data);
196 | }
197 |
198 | void update(const ros::Time& time, const ros::Duration& period)
199 | {
200 | std::vector & commands = *commands_buffer_.readFromRT();
201 | double dt = period.toSec();
202 | double q_cmd_old;
203 |
204 | // get joint states
205 | static double t = 0;
206 | for (size_t i=0; itype == urdf::Joint::REVOLUTE)
222 | {
223 | angles::shortest_angular_distance_with_limits(
224 | q_(i),
225 | q_cmd_(i),
226 | joint_urdfs_[i]->limits->lower,
227 | joint_urdfs_[i]->limits->upper,
228 | q_error_(i));
229 | }
230 | else if (joint_urdfs_[i]->type == urdf::Joint::CONTINUOUS)
231 | {
232 | q_error_(i) = angles::shortest_angular_distance(q_(i), q_cmd_(i));
233 | }
234 | else // prismatic
235 | {
236 | q_error_(i) = q_cmd_(i) - q_(i);
237 | }
238 | q_error_dot_(i) = qdot_cmd_(i) - qdot_(i);
239 |
240 | // friction compensation, to do: implement friction observer
241 | tau_fric_(i) = 1*qdot_(i) + 1*KDL::sign(qdot_(i));
242 | }
243 |
244 | t += dt;
245 |
246 | // compute gravity torque
247 | id_solver_->JntToGravity(q_, G_);
248 |
249 | // torque command
250 | for(int i=0; imsg_.effort_feedforward[i] = tau_cmd_(i);
255 | tau_cmd_(i) += pids_[i].computeCommand(q_error_(i), q_error_dot_(i), period);
256 |
257 | // effort saturation
258 | if (tau_cmd_(i) >= joint_urdfs_[i]->limits->effort)
259 | tau_cmd_(i) = joint_urdfs_[i]->limits->effort;
260 |
261 | if (tau_cmd_(i) <= -joint_urdfs_[i]->limits->effort)
262 | tau_cmd_(i) = -joint_urdfs_[i]->limits->effort;
263 |
264 | joints_[i].setCommand( tau_cmd_(i) );
265 | }
266 |
267 | // publish
268 | if (loop_count_ % 10 == 0)
269 | {
270 | if (controller_state_pub_->trylock())
271 | {
272 | controller_state_pub_->msg_.header.stamp = time;
273 | for(int i=0; imsg_.command[i] = R2D*q_cmd_(i);
276 | controller_state_pub_->msg_.command_dot[i] = R2D*qdot_cmd_(i);
277 | controller_state_pub_->msg_.state[i] = R2D*q_(i);
278 | controller_state_pub_->msg_.state_dot[i] = R2D*qdot_(i);
279 | controller_state_pub_->msg_.error[i] = R2D*q_error_(i);
280 | controller_state_pub_->msg_.error_dot[i] = R2D*q_error_dot_(i);
281 | controller_state_pub_->msg_.effort_command[i] = tau_cmd_(i);
282 |
283 | controller_state_pub_->msg_.effort_feedback[i] = tau_cmd_(i) - G_(i);
284 | }
285 | controller_state_pub_->unlockAndPublish();
286 | }
287 | }
288 | }
289 |
290 | void stopping(const ros::Time& time) { }
291 |
292 | void enforceJointLimits(double &command, unsigned int index)
293 | {
294 | // Check that this joint has applicable limits
295 | if (joint_urdfs_[index]->type == urdf::Joint::REVOLUTE || joint_urdfs_[index]->type == urdf::Joint::PRISMATIC)
296 | {
297 | if( command > joint_urdfs_[index]->limits->upper ) // above upper limnit
298 | {
299 | command = joint_urdfs_[index]->limits->upper;
300 | }
301 | else if( command < joint_urdfs_[index]->limits->lower ) // below lower limit
302 | {
303 | command = joint_urdfs_[index]->limits->lower;
304 | }
305 | }
306 | }
307 | private:
308 | int loop_count_;
309 |
310 | // joint handles
311 | unsigned int n_joints_;
312 | std::vector joint_names_;
313 | std::vector joints_;
314 | std::vector joint_urdfs_;
315 |
316 | // kdl
317 | KDL::Tree kdl_tree_;
318 | KDL::Chain kdl_chain_;
319 | boost::scoped_ptr id_solver_; // inverse dynamics solver
320 | KDL::JntArray G_; // gravity torque vector
321 | KDL::Vector gravity_;
322 |
323 | // cmd, state
324 | realtime_tools::RealtimeBuffer > commands_buffer_;
325 | KDL::JntArray q_cmd_, qdot_cmd_, qddot_cmd_;
326 | KDL::JntArray q_, qdot_;
327 |
328 | Eigen::VectorXd tau_cmd_, tau_fric_;
329 | Eigen::VectorXd q_error_, q_error_dot_;
330 |
331 | // gain
332 | std::vector pids_; /**< Internal PID controllers. */
333 |
334 | // topic
335 | ros::Subscriber command_sub_;
336 | boost::scoped_ptr<
337 | realtime_tools::RealtimePublisher<
338 | arm_controllers::ControllerJointState> > controller_state_pub_;
339 | };
340 |
341 | }
342 |
343 | PLUGINLIB_EXPORT_CLASS(arm_controllers::GravityCompController, controller_interface::ControllerBase)
344 |
345 |
--------------------------------------------------------------------------------
/arm_controllers/src/time_delay_controller.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 |
6 | #define PI 3.141592
7 | #define D2R PI/180.0
8 | #define R2D 180.0/PI
9 | #define JointMax 6
10 |
11 | namespace arm_controllers{
12 |
13 | class TimeDelayController: public controller_interface::Controller
14 | {
15 | public:
16 | bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n)
17 | {
18 | XmlRpc::XmlRpcValue my_joint;
19 | if (!n.getParam("joints", my_joint))
20 | {
21 | ROS_ERROR("Could not find joint name");
22 | return false;
23 | }
24 |
25 | if(my_joint.size() != JointMax)
26 | {
27 | ROS_ERROR("Wrong joint num");
28 | return false;
29 | }
30 |
31 | for(int i=0; igetHandle((std::string)name_value);
36 | joints_.push_back(joint);
37 | }
38 |
39 | pub_desired_pos_ = n.advertise("desired_pos", 1000);
40 | pub_current_pos_ = n.advertise("current_pos", 1000);
41 | pub_desired_vel_ = n.advertise("desired_vel", 1000);
42 | pub_current_vel_ = n.advertise("current_vel", 1000);
43 | pub_desired_acc_ = n.advertise("desired_acc", 1000);
44 | pub_current_acc_ = n.advertise("current_acc", 1000);
45 | pub_error_ = n.advertise("error", 1000);
46 | pub_error_vel_ = n.advertise("error_vel", 1000);
47 |
48 | return true;
49 | }
50 |
51 | void update(const ros::Time& time, const ros::Duration& period)
52 | {
53 | samplint_time_ = time.toSec() - last_time_;
54 |
55 | for(int i=0; i joints_;
158 |
159 | double last_time_;
160 | double samplint_time_;
161 | double count_;
162 |
163 | double init_pos_[JointMax];
164 | double desired_cmd_[JointMax];
165 | double desired_cmd_old_[JointMax];
166 | double desired_pos_[JointMax];
167 | double current_pos_[JointMax];
168 | double desired_vel_[JointMax];
169 | double current_vel_[JointMax];
170 | double current_vel_old_[JointMax];
171 | double desired_acc_[JointMax];
172 | double current_acc_[JointMax];
173 | double error_[JointMax];
174 | double error_vel_[JointMax];
175 | double ded_[JointMax];
176 | double tde_[JointMax];
177 |
178 | double mag_;
179 | double feq_;
180 |
181 | double Mbar_[JointMax];
182 |
183 | ros::Publisher pub_desired_pos_;
184 | ros::Publisher pub_current_pos_;
185 | ros::Publisher pub_desired_vel_;
186 | ros::Publisher pub_current_vel_;
187 | ros::Publisher pub_desired_acc_;
188 | ros::Publisher pub_current_acc_;
189 | ros::Publisher pub_error_;
190 | ros::Publisher pub_error_vel_;
191 |
192 | std_msgs::Float64MultiArray msg_desired_pos_;
193 | std_msgs::Float64MultiArray msg_current_pos_;
194 | std_msgs::Float64MultiArray msg_desired_vel_;
195 | std_msgs::Float64MultiArray msg_current_vel_;
196 | std_msgs::Float64MultiArray msg_desired_acc_;
197 | std_msgs::Float64MultiArray msg_current_acc_;
198 | std_msgs::Float64MultiArray msg_error_;
199 | std_msgs::Float64MultiArray msg_error_vel_;
200 |
201 | };
202 |
203 | }
204 |
205 | PLUGINLIB_EXPORT_CLASS(arm_controllers::TimeDelayController,controller_interface::ControllerBase)
206 |
207 |
--------------------------------------------------------------------------------
/elfin/elfin_description/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(elfin_description)
3 |
4 | ## Find catkin macros and libraries
5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
6 | ## is used, also find other catkin packages
7 | find_package(catkin REQUIRED COMPONENTS
8 | urdf
9 | )
10 |
11 | ## System dependencies are found with CMake's conventions
12 | # find_package(Boost REQUIRED COMPONENTS system)
13 |
14 |
15 | ## Uncomment this if the package has a setup.py. This macro ensures
16 | ## modules and global scripts declared therein get installed
17 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
18 | # catkin_python_setup()
19 |
20 | ################################################
21 | ## Declare ROS messages, services and actions ##
22 | ################################################
23 |
24 | ## To declare and build messages, services or actions from within this
25 | ## package, follow these steps:
26 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
27 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
28 | ## * In the file package.xml:
29 | ## * add a build_depend tag for "message_generation"
30 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
31 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
32 | ## but can be declared for certainty nonetheless:
33 | ## * add a run_depend tag for "message_runtime"
34 | ## * In this file (CMakeLists.txt):
35 | ## * add "message_generation" and every package in MSG_DEP_SET to
36 | ## find_package(catkin REQUIRED COMPONENTS ...)
37 | ## * add "message_runtime" and every package in MSG_DEP_SET to
38 | ## catkin_package(CATKIN_DEPENDS ...)
39 | ## * uncomment the add_*_files sections below as needed
40 | ## and list every .msg/.srv/.action file to be processed
41 | ## * uncomment the generate_messages entry below
42 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
43 |
44 | ## Generate messages in the 'msg' folder
45 | # add_message_files(
46 | # FILES
47 | # Message1.msg
48 | # Message2.msg
49 | # )
50 |
51 | ## Generate services in the 'srv' folder
52 | # add_service_files(
53 | # FILES
54 | # Service1.srv
55 | # Service2.srv
56 | # )
57 |
58 | ## Generate actions in the 'action' folder
59 | # add_action_files(
60 | # FILES
61 | # Action1.action
62 | # Action2.action
63 | # )
64 |
65 | ## Generate added messages and services with any dependencies listed here
66 | # generate_messages(
67 | # DEPENDENCIES
68 | # std_msgs # Or other packages containing msgs
69 | # )
70 |
71 | ################################################
72 | ## Declare ROS dynamic reconfigure parameters ##
73 | ################################################
74 |
75 | ## To declare and build dynamic reconfigure parameters within this
76 | ## package, follow these steps:
77 | ## * In the file package.xml:
78 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
79 | ## * In this file (CMakeLists.txt):
80 | ## * add "dynamic_reconfigure" to
81 | ## find_package(catkin REQUIRED COMPONENTS ...)
82 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
83 | ## and list every .cfg file to be processed
84 |
85 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
86 | # generate_dynamic_reconfigure_options(
87 | # cfg/DynReconf1.cfg
88 | # cfg/DynReconf2.cfg
89 | # )
90 |
91 | ###################################
92 | ## catkin specific configuration ##
93 | ###################################
94 | ## The catkin_package macro generates cmake config files for your package
95 | ## Declare things to be passed to dependent projects
96 | ## INCLUDE_DIRS: uncomment this if you package contains header files
97 | ## LIBRARIES: libraries you create in this project that dependent projects also need
98 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
99 | ## DEPENDS: system dependencies of this project that dependent projects also need
100 | catkin_package(
101 | # INCLUDE_DIRS include
102 | # LIBRARIES elfin_description
103 | # CATKIN_DEPENDS urdf
104 | # DEPENDS system_lib
105 | )
106 |
107 | ###########
108 | ## Build ##
109 | ###########
110 |
111 | ## Specify additional locations of header files
112 | ## Your package locations should be listed before other locations
113 | # include_directories(include)
114 | include_directories(
115 | ${catkin_INCLUDE_DIRS}
116 | )
117 |
118 | ## Declare a C++ library
119 | # add_library(elfin_description
120 | # src/${PROJECT_NAME}/elfin_description.cpp
121 | # )
122 |
123 | ## Add cmake target dependencies of the library
124 | ## as an example, code may need to be generated before libraries
125 | ## either from message generation or dynamic reconfigure
126 | # add_dependencies(elfin_description ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
127 |
128 | ## Declare a C++ executable
129 | # add_executable(elfin_description_node src/elfin_description_node.cpp)
130 |
131 | ## Add cmake target dependencies of the executable
132 | ## same as for the library above
133 | # add_dependencies(elfin_description_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
134 |
135 | ## Specify libraries to link a library or executable target against
136 | # target_link_libraries(elfin_description_node
137 | # ${catkin_LIBRARIES}
138 | # )
139 |
140 | #############
141 | ## Install ##
142 | #############
143 |
144 | # all install targets should use catkin DESTINATION variables
145 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
146 |
147 | ## Mark executable scripts (Python etc.) for installation
148 | ## in contrast to setup.py, you can choose the destination
149 | # install(PROGRAMS
150 | # scripts/my_python_script
151 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
152 | # )
153 |
154 | ## Mark executables and/or libraries for installation
155 | # install(TARGETS elfin_description elfin_description_node
156 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
157 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
158 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
159 | # )
160 |
161 | ## Mark cpp header files for installation
162 | # install(DIRECTORY include/${PROJECT_NAME}/
163 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
164 | # FILES_MATCHING PATTERN "*.h"
165 | # PATTERN ".svn" EXCLUDE
166 | # )
167 |
168 | ## Mark other files for installation (e.g. launch and bag files, etc.)
169 | # install(FILES
170 | # # myfile1
171 | # # myfile2
172 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
173 | # )
174 |
175 | #############
176 | ## Testing ##
177 | #############
178 |
179 | ## Add gtest based cpp test target and link libraries
180 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_elfin_description.cpp)
181 | # if(TARGET ${PROJECT_NAME}-test)
182 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
183 | # endif()
184 |
185 | ## Add folders to be run by python nosetests
186 | # catkin_add_nosetests(test)
187 |
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_base.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_base.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link1.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link1.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link2.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link2.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link3.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link3.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link4.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link4.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link5.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link5.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin10/elfin_link6.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin10/elfin_link6.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_base.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_base.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link1.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link1.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link2.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link2.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link3.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link3.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link4.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link4.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link5.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link5.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin3/elfin_link6.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin3/elfin_link6.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_base.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_base.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link1.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link1.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link2.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link2.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link3.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link3.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link4.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link4.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link5.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link5.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/meshes/elfin5/elfin_link6.STL:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/modulabs/arm-control/bbf53795d9cef18a91f4e96bff1c88f595f06a7b/elfin/elfin_description/meshes/elfin5/elfin_link6.STL
--------------------------------------------------------------------------------
/elfin/elfin_description/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | elfin_description
4 | 0.0.0
5 | The elfin_description package
6 |
7 |
8 |
9 |
10 | Cong Liu
11 |
12 |
13 |
14 |
15 |
16 | BSD
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 | Cong Liu
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 | catkin
44 | urdf
45 | urdf
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/box.urdf.xacro:
--------------------------------------------------------------------------------
1 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
23 |
25 |
27 |
28 |
29 |
30 | true
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/box_circle.urdf.xacro:
--------------------------------------------------------------------------------
1 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
34 |
36 |
38 |
39 |
40 |
41 | true
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin3.urdf.xacro:
--------------------------------------------------------------------------------
1 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
20 |
22 |
24 |
25 |
26 |
27 |
28 |
29 |
32 |
34 |
36 |
37 |
38 |
40 |
41 |
44 |
46 |
53 |
54 |
55 |
58 |
59 |
61 |
62 |
64 |
65 |
66 |
69 |
70 |
72 |
73 |
74 |
75 |
77 |
78 |
81 |
83 |
90 |
91 |
92 |
95 |
96 |
98 |
99 |
101 |
102 |
103 |
106 |
107 |
109 |
110 |
111 |
112 |
115 |
118 |
120 |
122 |
124 |
127 |
132 |
133 |
135 |
136 |
139 |
141 |
148 |
149 |
150 |
153 |
154 |
156 |
157 |
159 |
160 |
161 |
164 |
165 |
167 |
168 |
169 |
170 |
173 |
176 |
178 |
180 |
182 |
185 |
190 |
191 |
193 |
194 |
197 |
199 |
206 |
207 |
208 |
211 |
212 |
214 |
215 |
217 |
218 |
219 |
222 |
223 |
225 |
226 |
227 |
228 |
231 |
234 |
236 |
238 |
240 |
243 |
248 |
249 |
251 |
252 |
255 |
257 |
264 |
265 |
266 |
269 |
270 |
272 |
273 |
275 |
276 |
277 |
280 |
281 |
283 |
284 |
285 |
286 |
289 |
292 |
294 |
296 |
298 |
301 |
306 |
307 |
309 |
310 |
313 |
315 |
322 |
323 |
324 |
327 |
328 |
330 |
331 |
333 |
334 |
335 |
338 |
339 |
341 |
342 |
343 |
344 |
347 |
350 |
352 |
354 |
356 |
359 |
364 |
365 |
367 |
368 |
371 |
373 |
380 |
381 |
382 |
385 |
386 |
388 |
389 |
391 |
392 |
393 |
396 |
397 |
399 |
400 |
401 |
402 |
405 |
408 |
410 |
412 |
414 |
417 |
422 |
423 |
424 |
425 |
426 |
427 |
430 |
432 |
434 |
435 |
436 |
437 |
438 |
439 |
442 |
444 |
446 |
447 |
448 |
449 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin3_experiment1.urdf.xacro:
--------------------------------------------------------------------------------
1 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
18 |
20 |
22 |
23 |
24 |
25 |
26 |
27 |
30 |
32 |
34 |
35 |
36 |
38 |
39 |
42 |
44 |
51 |
52 |
53 |
56 |
57 |
59 |
60 |
62 |
63 |
64 |
67 |
68 |
70 |
71 |
72 |
73 |
75 |
76 |
79 |
81 |
88 |
89 |
90 |
93 |
94 |
96 |
97 |
99 |
100 |
101 |
104 |
105 |
107 |
108 |
109 |
110 |
113 |
116 |
118 |
120 |
122 |
125 |
130 |
131 |
133 |
134 |
137 |
139 |
146 |
147 |
148 |
151 |
152 |
154 |
155 |
157 |
158 |
159 |
162 |
163 |
165 |
166 |
167 |
168 |
171 |
174 |
176 |
178 |
180 |
183 |
188 |
189 |
191 |
192 |
195 |
197 |
204 |
205 |
206 |
209 |
210 |
212 |
213 |
215 |
216 |
217 |
220 |
221 |
223 |
224 |
225 |
226 |
229 |
232 |
234 |
236 |
238 |
241 |
246 |
247 |
249 |
250 |
253 |
255 |
262 |
263 |
264 |
267 |
268 |
270 |
271 |
273 |
274 |
275 |
278 |
279 |
281 |
282 |
283 |
284 |
287 |
290 |
292 |
294 |
296 |
299 |
304 |
305 |
307 |
308 |
311 |
313 |
320 |
321 |
322 |
325 |
326 |
328 |
329 |
331 |
332 |
333 |
336 |
337 |
339 |
340 |
341 |
342 |
345 |
348 |
350 |
352 |
354 |
357 |
362 |
363 |
365 |
366 |
369 |
371 |
378 |
379 |
380 |
383 |
384 |
386 |
387 |
389 |
390 |
391 |
394 |
395 |
397 |
398 |
399 |
400 |
403 |
406 |
408 |
410 |
412 |
415 |
420 |
421 |
422 |
423 |
424 |
425 |
426 |
427 |
428 |
429 |
430 |
431 |
432 |
433 |
434 |
435 |
436 |
437 |
438 |
439 |
440 |
441 |
442 |
443 |
444 |
445 |
446 |
447 |
448 |
449 |
454 |
455 |
456 |
457 |
458 |
459 |
460 |
461 |
462 |
463 |
464 |
465 |
466 |
467 |
468 |
469 |
470 |
471 |
472 |
473 |
474 |
475 |
476 |
477 |
478 |
479 |
480 |
481 |
482 |
483 |
484 |
485 |
486 |
487 |
488 |
489 |
490 |
491 |
492 |
493 |
494 |
495 |
496 |
497 |
498 |
499 |
500 |
501 |
502 |
503 |
504 |
505 |
506 |
507 |
508 |
509 |
510 |
511 |
512 |
513 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin3_no_fric_no_joint_limit.urdf.xacro:
--------------------------------------------------------------------------------
1 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
18 |
20 |
22 |
23 |
24 |
25 |
26 |
27 |
30 |
32 |
34 |
35 |
36 |
38 |
39 |
42 |
44 |
51 |
52 |
53 |
56 |
57 |
59 |
60 |
62 |
63 |
64 |
67 |
68 |
70 |
71 |
72 |
73 |
75 |
76 |
79 |
81 |
88 |
89 |
90 |
93 |
94 |
96 |
97 |
99 |
100 |
101 |
104 |
105 |
107 |
108 |
109 |
110 |
113 |
116 |
118 |
120 |
122 |
125 |
126 |
128 |
129 |
132 |
134 |
141 |
142 |
143 |
146 |
147 |
149 |
150 |
152 |
153 |
154 |
157 |
158 |
160 |
161 |
162 |
163 |
166 |
169 |
171 |
173 |
175 |
178 |
179 |
181 |
182 |
185 |
187 |
194 |
195 |
196 |
199 |
200 |
202 |
203 |
205 |
206 |
207 |
210 |
211 |
213 |
214 |
215 |
216 |
219 |
222 |
224 |
226 |
228 |
231 |
232 |
234 |
235 |
238 |
240 |
247 |
248 |
249 |
252 |
253 |
255 |
256 |
258 |
259 |
260 |
263 |
264 |
266 |
267 |
268 |
269 |
272 |
275 |
277 |
279 |
281 |
284 |
285 |
287 |
288 |
291 |
293 |
300 |
301 |
302 |
305 |
306 |
308 |
309 |
311 |
312 |
313 |
316 |
317 |
319 |
320 |
321 |
322 |
325 |
328 |
330 |
332 |
334 |
337 |
338 |
340 |
341 |
344 |
346 |
353 |
354 |
355 |
358 |
359 |
361 |
362 |
364 |
365 |
366 |
369 |
370 |
372 |
373 |
374 |
375 |
378 |
381 |
383 |
385 |
387 |
390 |
391 |
392 |
393 |
394 |
395 |
398 |
400 |
402 |
403 |
404 |
405 |
406 |
407 |
410 |
412 |
414 |
415 |
416 |
417 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin_robot.gazebo:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | /elfin
8 | gazebo_ros_control/DefaultRobotHWSim
9 | 0.001
10 |
11 |
12 |
13 |
14 |
15 |
16 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
31 |
32 |
33 |
34 |
35 |
36 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin_robot_experiment1.gazebo:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | /elfin
8 | gazebo_ros_control/DefaultRobotHWSim
9 | 0.001
10 |
11 |
12 |
13 |
14 | true
15 |
16 |
17 |
18 |
19 | 200
20 | elfin/ft_sensor_topic
21 | ft_sensor_joint
22 |
23 |
24 |
25 |
26 |
27 |
28 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
65 |
66 |
67 |
68 |
69 |
70 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin_transmission.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | transmission_interface/SimpleTransmission
6 |
7 | hardware_interface/EffortJointInterface
8 |
9 |
10 | hardware_interface/EffortJointInterface
11 | 1
12 |
13 |
14 |
15 |
16 | transmission_interface/SimpleTransmission
17 |
18 | hardware_interface/EffortJointInterface
19 |
20 |
21 | 1
22 |
23 |
24 |
25 |
26 | transmission_interface/SimpleTransmission
27 |
28 | hardware_interface/EffortJointInterface
29 |
30 |
31 | 1
32 |
33 |
34 |
35 |
36 | transmission_interface/SimpleTransmission
37 |
38 | hardware_interface/EffortJointInterface
39 |
40 |
41 | 1
42 |
43 |
44 |
45 |
46 | transmission_interface/SimpleTransmission
47 |
48 | hardware_interface/EffortJointInterface
49 |
50 |
51 | 1
52 |
53 |
54 |
55 |
56 | transmission_interface/SimpleTransmission
57 |
58 | hardware_interface/EffortJointInterface
59 |
60 |
61 | 1
62 |
63 |
64 |
65 |
66 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/elfin_transmission_experiment1.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | transmission_interface/SimpleTransmission
6 |
7 | hardware_interface/EffortJointInterface
8 |
9 |
10 | hardware_interface/EffortJointInterface
11 | 1
12 |
13 |
14 |
15 |
16 | transmission_interface/SimpleTransmission
17 |
18 | hardware_interface/EffortJointInterface
19 |
20 |
21 | 1
22 |
23 |
24 |
25 |
26 | transmission_interface/SimpleTransmission
27 |
28 | hardware_interface/EffortJointInterface
29 |
30 |
31 | 1
32 |
33 |
34 |
35 |
36 | transmission_interface/SimpleTransmission
37 |
38 | hardware_interface/EffortJointInterface
39 |
40 |
41 | 1
42 |
43 |
44 |
45 |
46 | transmission_interface/SimpleTransmission
47 |
48 | hardware_interface/EffortJointInterface
49 |
50 |
51 | 1
52 |
53 |
54 |
55 |
56 | transmission_interface/SimpleTransmission
57 |
58 | hardware_interface/EffortJointInterface
59 |
60 |
61 | 1
62 |
63 |
64 |
65 |
66 | transmission_interface/SimpleTransmission
67 |
68 | hardware_interface/EffortJointInterface
69 |
70 |
71 | 1
72 |
73 |
74 |
75 |
76 |
--------------------------------------------------------------------------------
/elfin/elfin_description/urdf/materials.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/.vscode/c_cpp_properties.json:
--------------------------------------------------------------------------------
1 | {
2 | "configurations": [
3 | {
4 | "browse": {
5 | "databaseFilename": "",
6 | "limitSymbolsToIncludedHeaders": true
7 | },
8 | "includePath": [
9 | "/opt/ros/kinetic/include",
10 | "/usr/include"
11 | ],
12 | "name": "Linux"
13 | }
14 | ]
15 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/.vscode/settings.json:
--------------------------------------------------------------------------------
1 | {
2 | "python.autoComplete.extraPaths": [
3 | "/opt/ros/kinetic/lib/python2.7/dist-packages"
4 | ]
5 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(elfin_gazebo)
3 |
4 | find_package(catkin REQUIRED)
5 |
6 | catkin_package()
7 |
8 | install(DIRECTORY launch
9 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
10 |
11 | install(DIRECTORY worlds
12 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
13 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/adaptive_impedance_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | adaptive_impedance_controller:
7 | type: arm_controllers/AdaptiveImpedanceController
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 | - ft_sensor_joint
16 |
17 | root_link: elfin_base_link
18 | tip_link: elfin_tool_ball
19 |
20 | joint1:
21 | tdc: {mbar: 0.02, r: 10.0, a: 50.0, w: 0.004}
22 | joint2:
23 | tdc: {mbar: 0.02, r: 10.0, a: 50.0, w: 0.004}
24 | joint3:
25 | tdc: {mbar: 0.01, r: 10.0, a: 50.0, w: 0.004}
26 | joint4:
27 | tdc: {mbar: 0.004, r: 10.0, a: 50.0, w: 0.004}
28 | joint5:
29 | tdc: {mbar: 0.003, r: 10.0, a: 50.0, w: 0.004}
30 | joint6:
31 | tdc: {mbar: 0.001, r: 10.0, a: 50.0, w: 0.004}
32 | joint7:
33 | tdc: {mbar: 0.0, r: 0.0, a: 0.0, w: 0.0}
34 |
35 | aic: {fd: 20.0, m: 5.0, b: 300.0}
36 |
37 | # mode = 0 -> No Filter, Fd(fixed)
38 | # mode = 1 -> Filter, Fd(fixed)
39 | # mode = 2 -> Filter, Fd(sin)
40 |
41 | mode: 2
42 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/computed_torque_clik_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | computed_torque_clik_controller:
7 | type: arm_controllers/Computed_Torque_CLIK_Controller
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 |
16 | gains:
17 | elfin_joint1:
18 | pid: {p: 100.0, i: 0, d: 20.0}
19 | elfin_joint2:
20 | pid: {p: 100.0, i: 0, d: 20.0}
21 | elfin_joint3:
22 | pid: {p: 100.0, i: 0, d: 20.0}
23 | elfin_joint4:
24 | pid: {p: 100.0, i: 0, d: 20.0}
25 | elfin_joint5:
26 | pid: {p: 100.0, i: 0, d: 20.0}
27 | elfin_joint6:
28 | pid: {p: 100.0, i: 0, d: 20.0}
29 |
30 | root_link: world
31 | tip_link: elfin_link6
32 |
33 | ctr_obj: 1 # ctr_obj = 1: Regulation
34 | # ctr_obj = 2: Tracking
35 |
36 | ik_mode: 2 # open-loop inverse kinematics using jacobian
37 | # closed-loop inverse Kinematics using jacobian
38 |
39 | clik_gain: {K_regulation: 6.0, K_tracking: 1.0}
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/computed_torque_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | computed_torque_controller:
7 | type: arm_controllers/Computed_Torque_Controller
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 | gains:
16 | elfin_joint1:
17 | pid: {p: 100.0, i: 0, d: 20.0}
18 | elfin_joint2:
19 | pid: {p: 100.0, i: 0, d: 20.0}
20 | elfin_joint3:
21 | pid: {p: 100.0, i: 0, d: 20.0}
22 | elfin_joint4:
23 | pid: {p: 100.0, i: 0, d: 20.0}
24 | elfin_joint5:
25 | pid: {p: 100.0, i: 0, d: 20.0}
26 | elfin_joint6:
27 | pid: {p: 100.0, i: 0, d: 20.0}
28 | root_link: world
29 | tip_link: elfin_link6
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/gravity_comp_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | gravity_comp_controller:
7 | type: arm_controllers/GravityCompController
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 | gains:
16 | elfin_joint1:
17 | pid: {p: 200.0, i: 10, d: 10.0, i_clamp: 50, antiwindup: true}
18 | elfin_joint2:
19 | pid: {p: 100, i: 5, d: 20, i_clamp: 50, antiwindup: true}
20 | elfin_joint3:
21 | pid: {p: 200.0, i: 10, d: 0.0, i_clamp: 50, antiwindup: true}
22 | elfin_joint4:
23 | pid: {p: 200.0, i: 10, d: 0.0, i_clamp: 50, antiwindup: true}
24 | elfin_joint5:
25 | pid: {p: 200.0, i: 10, d: 5.0, i_clamp: 50, antiwindup: true}
26 | elfin_joint6:
27 | pid: {p: 200.0, i: 5, d: 5.0, i_clamp: 50, antiwindup: true}
28 | root_link: world
29 | tip_link: elfin_link6
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/passivity_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | passivity_controller:
7 | type: arm_controllers/PassivityController
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 | gains:
16 | alpha: 1
17 | elfin_joint1:
18 | pid: {p: 200.0, i: 10, d: 10.0, i_clamp: 50, antiwindup: true}
19 | elfin_joint2:
20 | pid: {p: 100, i: 5, d: 20, i_clamp: 50, antiwindup: true}
21 | elfin_joint3:
22 | pid: {p: 200.0, i: 10, d: 0.0, i_clamp: 50, antiwindup: true}
23 | elfin_joint4:
24 | pid: {p: 200.0, i: 10, d: 0.0, i_clamp: 50, antiwindup: true}
25 | elfin_joint5:
26 | pid: {p: 200.0, i: 10, d: 5.0, i_clamp: 50, antiwindup: true}
27 | elfin_joint6:
28 | pid: {p: 200.0, i: 5, d: 5.0, i_clamp: 50, antiwindup: true}
29 | root_link: world
30 | tip_link: elfin_link6
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/config/time_delay_controller.yaml:
--------------------------------------------------------------------------------
1 | elfin:
2 | joint_state_controller:
3 | type: joint_state_controller/JointStateController
4 | publish_rate: 1000
5 |
6 | time_delay_controller:
7 | type: arm_controllers/TimeDelayController
8 | joints:
9 | - elfin_joint1
10 | - elfin_joint2
11 | - elfin_joint3
12 | - elfin_joint4
13 | - elfin_joint5
14 | - elfin_joint6
15 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/elfin3_empty_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
16 |
17 |
18 |
20 |
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/elfin3_experiment1_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
21 |
22 |
23 |
25 |
26 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/elfin3_experiment2_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
21 |
22 |
23 |
25 |
26 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/elfin3_no_fric_no_joint_limit_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
16 |
17 |
18 |
20 |
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/gravity_comp_controller_perspective/joint6_effort.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/gravity_comp_controller/state/effort_command[5]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[222.079, 223.079]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u''"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-195.3578048789923, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[210.512, 211.512]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/gravity_comp_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('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')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint1_error.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/error[0]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[120.197, 121.197]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u'/elfin/passivity_controller/state/error_dot[5]'"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-193.6367471723984, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[120.15, 121.15]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('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')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint2_error.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/error[1]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[120.197, 121.197]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u'/elfin/passivity_controller/state/error_dot[1]'"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-193.6367471723984, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[120.15, 121.15]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000000fd00000001000000030000068e000003b4fc0100000007fb00000058007200710074005f007000750062006c00690073006800650072005f005f005000750062006c00690073006800650072005f005f0031005f005f005000750062006c0069007300680065007200570069006400670065007401000000000000026d0000000000000000fb000000b4007200710074005f006a006f0069006e0074005f007400720061006a006500630074006f00720079005f0063006f006e00740072006f006c006c00650072005f005f004a006f0069006e0074005400720061006a006500630074006f007200790043006f006e00740072006f006c006c00650072005f005f0031005f005f004a006f0069006e0074005400720061006a006500630074006f007200790043006f006e00740072006f006c006c006500720055006901000003be000001050000000000000000fb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0031005f005f00440061007400610050006c006f00740057006900640067006500740100000000000003510000013800fffffffb0000006c007200710074005f007200650063006f006e006600690067007500720065005f005f0050006100720061006d005f005f0031005f005f005f0070006c007500670069006e0063006f006e007400610069006e00650072005f0074006f0070005f00770069006400670065007401000003b1000003f50000000000000000fc000002ff0000038f0000000000fffffffc0200000002fb00000040007200710074005f007300680065006c006c005f005f005300680065006c006c005f005f0031005f005f005300680065006c006c005700690064006700650074010000001b000000750000000000000000fb00000044007200710074005f00670072006100700068005f005f0052006f007300470072006100700068005f005f0031005f005f0052006f00730047007200610070006800550069010000001b000003b40000000000000000fb00000050007200710074005f006400650070005f005f0052006f0073005000610063006b00470072006100700068005f005f0031005f005f0052006f0073005000610063006b00470072006100700068005500690100000395000002c30000000000000000fb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0032005f005f00440061007400610050006c006f00740057006900640067006500740100000357000003370000013800ffffff0000068e0000000000000004000000040000000800000008fc00000001000000030000000100000036004d0069006e0069006d0069007a006500640044006f0063006b00570069006400670065007400730054006f006f006c0062006100720000000000ffffffff0000000000000000')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint3_error.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/error[2]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[120.197, 121.197]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u'/elfin/passivity_controller/state/error_dot[2]'"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-193.6367471723984, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[120.15, 121.15]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('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')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint5_error.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/error[4]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[120.197, 121.197]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u'/elfin/passivity_controller/state/error_dot[4]'"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-193.6367471723984, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[120.15, 121.15]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000000fd00000001000000030000068e000003b4fc0100000007fb00000058007200710074005f007000750062006c00690073006800650072005f005f005000750062006c00690073006800650072005f005f0031005f005f005000750062006c0069007300680065007200570069006400670065007401000000000000026d0000000000000000fb000000b4007200710074005f006a006f0069006e0074005f007400720061006a006500630074006f00720079005f0063006f006e00740072006f006c006c00650072005f005f004a006f0069006e0074005400720061006a006500630074006f007200790043006f006e00740072006f006c006c00650072005f005f0031005f005f004a006f0069006e0074005400720061006a006500630074006f007200790043006f006e00740072006f006c006c006500720055006901000003be000001050000000000000000fb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0031005f005f00440061007400610050006c006f00740057006900640067006500740100000000000003510000013800fffffffb0000006c007200710074005f007200650063006f006e006600690067007500720065005f005f0050006100720061006d005f005f0031005f005f005f0070006c007500670069006e0063006f006e007400610069006e00650072005f0074006f0070005f00770069006400670065007401000003b1000003f50000000000000000fc000002ff0000038f0000000000fffffffc0200000002fb00000040007200710074005f007300680065006c006c005f005f005300680065006c006c005f005f0031005f005f005300680065006c006c005700690064006700650074010000001b000000750000000000000000fb00000044007200710074005f00670072006100700068005f005f0052006f007300470072006100700068005f005f0031005f005f0052006f00730047007200610070006800550069010000001b000003b40000000000000000fb00000050007200710074005f006400650070005f005f0052006f0073005000610063006b00470072006100700068005f005f0031005f005f0052006f0073005000610063006b00470072006100700068005500690100000395000002c30000000000000000fb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0032005f005f00440061007400610050006c006f00740057006900640067006500740100000357000003370000013800ffffff0000068e0000000000000004000000040000000800000008fc00000001000000030000000100000036004d0069006e0069006d0069007a006500640044006f0063006b00570069006400670065007400730054006f006f006c0062006100720000000000ffffffff0000000000000000')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint6_effort.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/effort_command[5]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[222.079, 223.079]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u''"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-195.3578048789923, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[210.512, 211.512]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('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')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/passivity_controller_perspective/joint6_error.perspective:
--------------------------------------------------------------------------------
1 | {
2 | "keys": {},
3 | "groups": {
4 | "pluginmanager": {
5 | "keys": {
6 | "running-plugins": {
7 | "type": "repr",
8 | "repr": "{u'rqt_plot/Plot': [2, 1]}"
9 | }
10 | },
11 | "groups": {
12 | "plugin__rqt_reconfigure__Param__1": {
13 | "keys": {},
14 | "groups": {
15 | "dock_widget___plugincontainer_top_widget": {
16 | "keys": {
17 | "dockable": {
18 | "type": "repr",
19 | "repr": "u'true'"
20 | },
21 | "parent": {
22 | "type": "repr",
23 | "repr": "None"
24 | },
25 | "dock_widget_title": {
26 | "type": "repr",
27 | "repr": "u'Dynamic Reconfigure'"
28 | }
29 | },
30 | "groups": {}
31 | },
32 | "plugin": {
33 | "keys": {
34 | "splitter": {
35 | "type": "repr(QByteArray.hex)",
36 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff0000000100000002000001c00000022f01ffffffff010000000100')",
37 | "pretty-print": " / "
38 | },
39 | "_splitter": {
40 | "type": "repr(QByteArray.hex)",
41 | "repr(QByteArray.hex)": "QtCore.QByteArray('000000ff00000001000000020000012c000000640100000009010000000200')",
42 | "pretty-print": " , d "
43 | }
44 | },
45 | "groups": {}
46 | }
47 | }
48 | },
49 | "plugin__rqt_plot__Plot__1": {
50 | "keys": {},
51 | "groups": {
52 | "dock_widget__DataPlotWidget": {
53 | "keys": {
54 | "dockable": {
55 | "type": "repr",
56 | "repr": "True"
57 | },
58 | "parent": {
59 | "type": "repr",
60 | "repr": "None"
61 | },
62 | "dock_widget_title": {
63 | "type": "repr",
64 | "repr": "u'MatPlot'"
65 | }
66 | },
67 | "groups": {}
68 | },
69 | "plugin": {
70 | "keys": {
71 | "autoscroll": {
72 | "type": "repr",
73 | "repr": "True"
74 | },
75 | "plot_type": {
76 | "type": "repr",
77 | "repr": "1"
78 | },
79 | "topics": {
80 | "type": "repr",
81 | "repr": "u'/elfin/passivity_controller/state/error[5]'"
82 | },
83 | "y_limits": {
84 | "type": "repr",
85 | "repr": "[-44.99999924915964, 44.99999925452271]"
86 | },
87 | "x_limits": {
88 | "type": "repr",
89 | "repr": "[120.197, 121.197]"
90 | }
91 | },
92 | "groups": {}
93 | }
94 | }
95 | },
96 | "plugin__rqt_plot__Plot__2": {
97 | "keys": {},
98 | "groups": {
99 | "dock_widget__DataPlotWidget": {
100 | "keys": {
101 | "dockable": {
102 | "type": "repr",
103 | "repr": "True"
104 | },
105 | "parent": {
106 | "type": "repr",
107 | "repr": "None"
108 | },
109 | "dock_widget_title": {
110 | "type": "repr",
111 | "repr": "u'MatPlot (2)'"
112 | }
113 | },
114 | "groups": {}
115 | },
116 | "plugin": {
117 | "keys": {
118 | "autoscroll": {
119 | "type": "repr",
120 | "repr": "True"
121 | },
122 | "plot_type": {
123 | "type": "repr",
124 | "repr": "1"
125 | },
126 | "topics": {
127 | "type": "repr",
128 | "repr": "u'/elfin/passivity_controller/state/error_dot[5]'"
129 | },
130 | "y_limits": {
131 | "type": "repr",
132 | "repr": "[-193.6367471723984, 195.28958766075576]"
133 | },
134 | "x_limits": {
135 | "type": "repr",
136 | "repr": "[120.15, 121.15]"
137 | }
138 | },
139 | "groups": {}
140 | }
141 | }
142 | },
143 | "plugin__rqt_shell__Shell__1": {
144 | "keys": {},
145 | "groups": {
146 | "plugin": {
147 | "keys": {
148 | "shell_type": {
149 | "type": "repr",
150 | "repr": "u'2'"
151 | }
152 | },
153 | "groups": {}
154 | }
155 | }
156 | },
157 | "plugin__rqt_graph__RosGraph__1": {
158 | "keys": {},
159 | "groups": {
160 | "dock_widget__RosGraphUi": {
161 | "keys": {
162 | "dockable": {
163 | "type": "repr",
164 | "repr": "u'true'"
165 | },
166 | "parent": {
167 | "type": "repr",
168 | "repr": "None"
169 | },
170 | "dock_widget_title": {
171 | "type": "repr",
172 | "repr": "u'Node Graph'"
173 | }
174 | },
175 | "groups": {}
176 | },
177 | "plugin": {
178 | "keys": {
179 | "graph_type_combo_box_index": {
180 | "type": "repr",
181 | "repr": "u'1'"
182 | },
183 | "topic_filter_line_edit_text": {
184 | "type": "repr",
185 | "repr": "u'/'"
186 | },
187 | "filter_line_edit_text": {
188 | "type": "repr",
189 | "repr": "u'/'"
190 | },
191 | "highlight_connections_check_box_state": {
192 | "type": "repr",
193 | "repr": "u'true'"
194 | },
195 | "unreachable_check_box_state": {
196 | "type": "repr",
197 | "repr": "u'true'"
198 | },
199 | "actionlib_check_box_state": {
200 | "type": "repr",
201 | "repr": "u'true'"
202 | },
203 | "quiet_check_box_state": {
204 | "type": "repr",
205 | "repr": "u'true'"
206 | },
207 | "dead_sinks_check_box_state": {
208 | "type": "repr",
209 | "repr": "u'true'"
210 | },
211 | "leaf_topics_check_box_state": {
212 | "type": "repr",
213 | "repr": "u'true'"
214 | },
215 | "namespace_cluster_check_box_state": {
216 | "type": "repr",
217 | "repr": "u'true'"
218 | },
219 | "auto_fit_graph_check_box_state": {
220 | "type": "repr",
221 | "repr": "u'true'"
222 | }
223 | },
224 | "groups": {}
225 | }
226 | }
227 | },
228 | "plugin__rqt_publisher__Publisher__1": {
229 | "keys": {},
230 | "groups": {
231 | "dock_widget__PublisherWidget": {
232 | "keys": {
233 | "dockable": {
234 | "type": "repr",
235 | "repr": "u'true'"
236 | },
237 | "parent": {
238 | "type": "repr",
239 | "repr": "None"
240 | },
241 | "dock_widget_title": {
242 | "type": "repr",
243 | "repr": "u'Message Publisher'"
244 | }
245 | },
246 | "groups": {}
247 | },
248 | "plugin": {
249 | "keys": {
250 | "publishers": {
251 | "type": "repr",
252 | "repr": "u\"[{'type_name': 'std_msgs/Float64MultiArray', 'topic_name': '/elfin/passivity_controller/command', 'enabled': False, 'rate': 1.0, 'expressions': {}, 'publisher_id': 0, 'counter': 0}]\""
253 | }
254 | },
255 | "groups": {}
256 | }
257 | }
258 | },
259 | "plugin__rqt_joint_trajectory_controller__JointTrajectoryController__1": {
260 | "keys": {},
261 | "groups": {
262 | "plugin": {
263 | "keys": {
264 | "jtc_name": {
265 | "type": "repr",
266 | "repr": "None"
267 | },
268 | "cm_ns": {
269 | "type": "repr",
270 | "repr": "u'/elfin/controller_manager'"
271 | }
272 | },
273 | "groups": {}
274 | }
275 | }
276 | },
277 | "plugin__rqt_dep__RosPackGraph__1": {
278 | "keys": {},
279 | "groups": {
280 | "plugin": {
281 | "keys": {
282 | "filter_line_edit_text": {
283 | "type": "repr",
284 | "repr": "u'(Separate pkgs by comma)'"
285 | },
286 | "highlight_connections_check_box_state": {
287 | "type": "repr",
288 | "repr": "u'true'"
289 | },
290 | "with_stacks_state": {
291 | "type": "repr",
292 | "repr": "u'true'"
293 | },
294 | "depth_combo_box_index": {
295 | "type": "repr",
296 | "repr": "u'0'"
297 | },
298 | "hide_transitives_state": {
299 | "type": "repr",
300 | "repr": "u'false'"
301 | },
302 | "package_type_combo_box": {
303 | "type": "repr",
304 | "repr": "u'0'"
305 | },
306 | "directions_combo_box_index": {
307 | "type": "repr",
308 | "repr": "u'0'"
309 | },
310 | "colorize_state": {
311 | "type": "repr",
312 | "repr": "u'false'"
313 | },
314 | "mark_state": {
315 | "type": "repr",
316 | "repr": "u'true'"
317 | },
318 | "show_system_state": {
319 | "type": "repr",
320 | "repr": "u'false'"
321 | },
322 | "auto_fit_graph_check_box_state": {
323 | "type": "repr",
324 | "repr": "u'true'"
325 | }
326 | },
327 | "groups": {}
328 | }
329 | }
330 | }
331 | }
332 | },
333 | "mainwindow": {
334 | "keys": {
335 | "geometry": {
336 | "type": "repr(QByteArray.hex)",
337 | "repr(QByteArray.hex)": "QtCore.QByteArray('01d9d0cb0002000000000000000000000000068f000003fe00000001000000190000068e000003fd00000000000000000690')",
338 | "pretty-print": " "
339 | },
340 | "state": {
341 | "type": "repr(QByteArray.hex)",
342 | "repr(QByteArray.hex)": "QtCore.QByteArray('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')",
343 | "pretty-print": " Xrqt_publisher__Publisher__1__PublisherWidget rqt_joint_trajectory_controller__JointTrajectoryController__1__JointTrajectoryControllerUi Brqt_plot__Plot__1__DataPlotWidget lrqt_reconfigure__Param__1___plugincontainer_top_widget u W 7 8 "
344 | }
345 | },
346 | "groups": {
347 | "toolbar_areas": {
348 | "keys": {
349 | "MinimizedDockWidgetsToolbar": {
350 | "type": "repr",
351 | "repr": "8"
352 | }
353 | },
354 | "groups": {}
355 | }
356 | }
357 | }
358 | }
359 | }
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/launch/rqt_plot.launch:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
7 |
8 |
10 |
11 |
13 |
14 |
--------------------------------------------------------------------------------
/elfin/elfin_gazebo/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | elfin_gazebo
4 | 0.0.0
5 | The elfin_gazebo package
6 |
7 |
8 |
9 |
10 | Cong Liu
11 |
12 |
13 |
14 |
15 |
16 | BSD
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 | Cong Liu
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 | catkin
44 | elfin_description
45 | gazebo_ros
46 | gazebo_ros_control
47 | elfin_description
48 | gazebo_ros
49 | gazebo_ros_control
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
--------------------------------------------------------------------------------