Open arnauddomes opened 2 years ago
franka_ros 0.9.0 panda_moveit_config 0.7.5
@arnauddomes I am on franka_ros
0.9.0 and see the same error. This seems to be related to #191. panda_moveit_config
noetic-devel
branch is broken and in melodic-devel
or v0.7.5, the move_group.launch
needs joint_states_desired
topic.
So a temporary workaround:
add to franka_control.launch
:
<node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
<rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired] </rosparam>
<param name="rate" value="30"/>
<remap from="/joint_states" to="/joint_states_desired" />
</node>
add to move_to_start.launch
:
<node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world panda_link0" />
Again this is just to get the franka - Moveit connection working again, a more permanent fix would be to wait for the developers to fix it properly.
Hello everyone, we have been working a lot with the above mentioned packages, and to reply to @samarth-robo
Using your solution we had to add a relay node in the main execution launch file to repeat the /joint_states_desired
topic in the /joint_states
topic as follows:
<node pkg="topic_tools" type="relay" name="relay_joint_info" args="joint_states_desired joint_states" output="screen"/>
yes that's a way to work around the problem, but with enough time and investigation we found out that there's a remap function
<remap from="/joint_states" to="/joint_states_desired" />
in line 78 of the move_group.launch
of the panda_moveit_config
package in the melodic-branch
removing this line made it work for us.
We don't know if it needs solving (and finally closing this issue), because in the noetic-branch
this line was already removed.
Hello,
Enrironnement: Ubuntu 20.04 Ros: Noetic Franka_ros : origin/noetic-devel
I try to launch move_to_start.launch on Panda arm like this;
roslaunch franka_example_controllers move_to_start.launch robot_ip:=172.16.0.2
I get that warning before the program stop:
Failed to validate trajectory: couldn't receive full current joint state within 1s
Here is the full log:
https://codeshare.io/kmDN4M