Aggiunta funzione per portare il robot in configurazione Home da

interfaccia grafica, da implementare
This commit is contained in:
2019-10-23 11:14:23 +02:00
parent a8149e5f72
commit 9798178623
3 changed files with 101 additions and 20 deletions

View File

@@ -23,7 +23,8 @@
<param name="OUTcoordinates" type="string" value="/roboglue_com/ros2com/coordinates" />
<param name="OUTdelta_jog" type="string" value="/jog_arm_server/delta_jog_cmds" />
<param name="OUTdelta_joint_jog" type="string" value="/jog_arm_server/delta_joint_jog_cmds" />
<param name="OUTtraj_jog" type="string" value="/pos_based_pos_traj_controller/command" />
<!-- For UR official driver use scalable position controller -->
<param name="OUTtraj_jog" type="string" value="/scaled_pos_traj_controller/command" />
<param name="robot_model_name" type="string" value="robot_description" />
<param name="move_group_name" type="string" value="manipulator" />
<param name="loop_rate" type="int" value="100" />

View File

@@ -9,6 +9,7 @@
20190308 - Inserita una funzione che si occupa di effettuare il blocco delle variaili.
20190325 - Implementato uso del ros parameter server per la configurazione del nodo.
Contiene i nomi delle code ros.
20191023 - Passaggio dei commenti a GIT
*/
////////// ROS INCLUDES /////////////
#include "ros/ros.h"
@@ -21,6 +22,7 @@
//////////////////////////////////////////
void testFunction( ros::Publisher* trj_pub);
trajectory_msgs::JointTrajectory composeTrjMessage(std::vector<double> jtpos);
bool resetModelJointsHome(geometry_msgs::Pose, bool);
///////////////////////////////////////////
///////// ROS CALLBACKS //////////////////
@@ -45,7 +47,9 @@ void commandCallback(const std_msgs::String::ConstPtr& msg, internalState* is, p
}
else ROS_ERROR("Invalid acton");
} else if (!command.compare("RECORD") || !command.compare("PLAY") || !command.compare("OPEN")) {
return;
return;
} else if (!command.compare("HOME")) {
// Chiamata alla funzione di reset dei giunti nel modello
} else {
ROS_WARN("Unknown command: %s", command.c_str());
}
@@ -242,6 +246,16 @@ int main(int argc, char **argv) {
///////////// END MAIN /////////////////
////////////////////////////////////////
// TODO: aggiungere la possibilità di resettare i giunti nella configurazione home a comando da interfaccia
bool resetModelJointsHome(geometry_msgs::Pose home_pos, bool execute=false) {{
ROS_DEBUG("Setting joint position to home");
if (execute){
return false;
} else {
return false;
}
}
trajectory_msgs::JointTrajectory composeTrjMessage(std::vector<double> jtpos){
static trajectory_msgs::JointTrajectory trj;
static double ang=0.0;