Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update missing dependencies #102

Open
wants to merge 6 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions lwr_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<depend>realtime_tools</depend>
<depend>urdf</depend>
<depend>forward_command_controller</depend>
<depend>joint_state_controller</depend>
<depend>dynamic_reconfigure</depend>
<depend>eigen</depend>
<depend>kdl_parser</depend>
Expand Down
30 changes: 19 additions & 11 deletions lwr_hw/include/lwr_hw/lwr_hw_fri.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,19 +196,27 @@ class LWRHWFRI : public LWRHW
}
else
{
ROS_INFO_STREAM_THROTTLE(1, "Desired strategy differs, trying to stop FRI.");
stopFRI();

// send to KRL the new strategy
if( desired_strategy == JOINT_POSITION )
if( desired_strategy == JOINT_POSITION ) {
ROS_INFO_STREAM_THROTTLE(1, "Switching to JOINT_POSITION");
device_->setToKRLInt(0, JOINT_POSITION);
else if( desired_strategy == JOINT_IMPEDANCE)
}
else if( desired_strategy == JOINT_IMPEDANCE) {
ROS_INFO_STREAM_THROTTLE(1, "Switching to JOINT_IMPEDANCE");
device_->setToKRLInt(0, JOINT_IMPEDANCE);
else if( desired_strategy == CARTESIAN_IMPEDANCE)
}
else if( desired_strategy == CARTESIAN_IMPEDANCE) {
ROS_INFO_STREAM_THROTTLE(1, "Switching to CARTESIAN_IMPEDANCE");
device_->setToKRLInt(0, CARTESIAN_IMPEDANCE);
}


ROS_INFO_STREAM_THROTTLE(1, "Starting FRI");
startFRI();

ROS_INFO_STREAM_THROTTLE(1, "Set control strategy");
setControlStrategy(desired_strategy);
std::cout << "The ControlStrategy changed to: " << getControlStrategy() << std::endl;
}
Expand Down Expand Up @@ -265,13 +273,13 @@ class LWRHWFRI : public LWRHW
// wait until FRI enters in command mode
device_->setToKRLInt(1, 0);
std::cout << "Waiting for monitor mode..." << std::endl;
while ( device_->getFrmKRLInt(1) != 0 ){}
// {
// std::cout << "device_->getState(): " << device_->getState() << std::endl;
// std::cout << "Waiting for monitor mode..." << std::endl;
// device_->setToKRLInt(1, 0);
// usleep(1000000);
// }
while ( device_->getFrmKRLInt(1) != 0 )
{
std::cout << "device_->getState(): " << device_->getState() << std::endl;
std::cout << "Waiting for monitor mode..." << std::endl;
device_->setToKRLInt(1, 0);
usleep(500000);
}
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<!-- Everythings is spawned under a namespace with the same name as the robot's. -->

<arg name="hardware_interface" default="PositionJointInterface"/>
<arg name="controllers" default="joint_state_controller pos_joint_trajectory_controller"/>
<arg name="controllers" default="joint_state_controller joint_trajectory_controller"/>
<arg name="robot_name" default="iiwa" />
<arg name="model" default="iiwa7" />

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@

<include file="$(find single_lwr_launch)/launch/lwr_control.launch">
<arg name="hardware_interface" value="$(arg hardware_interface)" />
<arg name="controllers" value="joint_state_controller $(arg hardware_interface)_trajectory_controller" />
<arg name="controllers" value="joint_state_controller joint_trajectory_controller" />
<arg name="robot_name" value="$(arg robot_name)" />
<arg name="model" value="$(arg model)" />
</include>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,3 @@ full_lwr:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.05 #default: 0.005
kinematics_solver_attempts: 20 #default: 3
26 changes: 12 additions & 14 deletions single_lwr_example/single_lwr_moveit/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -70,11 +70,6 @@ Visualization Manager:
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
box:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lwr_1_link:
Alpha: 1
Show Axes: false
Expand Down Expand Up @@ -143,6 +138,10 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
world:
Alpha: 1
Show Axes: false
Show Trail: false
Loop Animation: true
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Expand Down Expand Up @@ -188,11 +187,6 @@ Visualization Manager:
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
box:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lwr_1_link:
Alpha: 1
Show Axes: false
Expand Down Expand Up @@ -261,6 +255,10 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
world:
Alpha: 1
Show Axes: false
Show Trail: false
Robot Alpha: 0.5
Show Robot Collision: false
Show Robot Visual: true
Expand All @@ -271,8 +269,6 @@ Visualization Manager:
Frame Timeout: 15
Frames:
All Enabled: false
box:
Value: false
lwr_1_link:
Value: false
lwr_1_link_dummy:
Expand Down Expand Up @@ -303,13 +299,15 @@ Visualization Manager:
Value: false
lwr_base_link:
Value: true
world:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
box:
world:
lwr_base_link:
lwr_1_link:
lwr_2_link:
Expand Down Expand Up @@ -339,7 +337,7 @@ Visualization Manager:
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: box
Fixed Frame: world
Frame Rate: 30
Name: root
Tools:
Expand Down
1 change: 1 addition & 0 deletions single_lwr_example/single_lwr_moveit/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_planners_ompl</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_simple_controller_manager</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>xacro</exec_depend>
Expand Down
2 changes: 2 additions & 0 deletions single_lwr_example/single_lwr_robot/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
<exec_depend>lwr_hw</exec_depend>
<exec_depend>lwr_description</exec_depend>
<exec_depend>lwr_controllers</exec_depend>
<exec_depend>joint_trajectory_controller</exec_depend>
<exec_depend>position_controllers</exec_depend>

<export>
</export>
Expand Down